mirror of
https://github.com/dalathegreat/Battery-Emulator.git
synced 2025-10-05 02:39:57 +02:00
Merge pull request #1287 from kyberias/hal2
Hal refactoring and GPIO allocations
This commit is contained in:
commit
342090f3b8
109 changed files with 2712 additions and 1914 deletions
|
@ -54,4 +54,5 @@ jobs:
|
||||||
- name: Upload artifact
|
- name: Upload artifact
|
||||||
uses: actions/upload-artifact@v4
|
uses: actions/upload-artifact@v4
|
||||||
with:
|
with:
|
||||||
|
name: battery-emulator-lilygo.bin
|
||||||
path: Software.ino.bin
|
path: Software.ino.bin
|
||||||
|
|
|
@ -17,33 +17,17 @@
|
||||||
#include "src/communication/precharge_control/precharge_control.h"
|
#include "src/communication/precharge_control/precharge_control.h"
|
||||||
#include "src/communication/rs485/comm_rs485.h"
|
#include "src/communication/rs485/comm_rs485.h"
|
||||||
#include "src/datalayer/datalayer.h"
|
#include "src/datalayer/datalayer.h"
|
||||||
|
#include "src/devboard/mqtt/mqtt.h"
|
||||||
#include "src/devboard/sdcard/sdcard.h"
|
#include "src/devboard/sdcard/sdcard.h"
|
||||||
#include "src/devboard/utils/events.h"
|
#include "src/devboard/utils/events.h"
|
||||||
#include "src/devboard/utils/led_handler.h"
|
#include "src/devboard/utils/led_handler.h"
|
||||||
#include "src/devboard/utils/logging.h"
|
#include "src/devboard/utils/logging.h"
|
||||||
#include "src/devboard/utils/timer.h"
|
#include "src/devboard/utils/timer.h"
|
||||||
#include "src/devboard/utils/value_mapping.h"
|
#include "src/devboard/utils/value_mapping.h"
|
||||||
#include "src/include.h"
|
|
||||||
#ifndef AP_PASSWORD
|
|
||||||
#error \
|
|
||||||
"Initial setup not completed, USER_SECRETS.h is missing. Please rename the file USER_SECRETS.TEMPLATE.h to USER_SECRETS.h and fill in the required credentials. This file is ignored by version control to keep sensitive information private."
|
|
||||||
#endif
|
|
||||||
#ifdef WIFI
|
|
||||||
#include "src/devboard/wifi/wifi.h"
|
|
||||||
#ifdef WEBSERVER
|
|
||||||
#include "src/devboard/webserver/webserver.h"
|
#include "src/devboard/webserver/webserver.h"
|
||||||
#ifdef MDNSRESPONDER
|
#include "src/devboard/wifi/wifi.h"
|
||||||
#include <ESPmDNS.h>
|
#include "src/include.h"
|
||||||
#endif // MDNSRESONDER
|
|
||||||
#else // WEBSERVER
|
|
||||||
#ifdef MDNSRESPONDER
|
|
||||||
#error WEBSERVER needs to be enabled for MDNSRESPONDER!
|
|
||||||
#endif // MDNSRSPONDER
|
|
||||||
#endif // WEBSERVER
|
|
||||||
#ifdef MQTT
|
|
||||||
#include "src/devboard/mqtt/mqtt.h"
|
|
||||||
#endif // MQTT
|
|
||||||
#endif // WIFI
|
|
||||||
#ifdef PERIODIC_BMS_RESET_AT
|
#ifdef PERIODIC_BMS_RESET_AT
|
||||||
#include "src/devboard/utils/ntp_time.h"
|
#include "src/devboard/utils/ntp_time.h"
|
||||||
#endif
|
#endif
|
||||||
|
@ -70,6 +54,8 @@ Logging logging;
|
||||||
|
|
||||||
// Initialization
|
// Initialization
|
||||||
void setup() {
|
void setup() {
|
||||||
|
init_hal();
|
||||||
|
|
||||||
init_serial();
|
init_serial();
|
||||||
|
|
||||||
// We print this after setting up serial, such that is also printed to serial with DEBUG_VIA_USB set.
|
// We print this after setting up serial, such that is also printed to serial with DEBUG_VIA_USB set.
|
||||||
|
@ -79,35 +65,48 @@ void setup() {
|
||||||
|
|
||||||
init_stored_settings();
|
init_stored_settings();
|
||||||
|
|
||||||
#ifdef WIFI
|
if (wifi_enabled) {
|
||||||
xTaskCreatePinnedToCore((TaskFunction_t)&connectivity_loop, "connectivity_loop", 4096, NULL, TASK_CONNECTIVITY_PRIO,
|
xTaskCreatePinnedToCore((TaskFunction_t)&connectivity_loop, "connectivity_loop", 4096, NULL, TASK_CONNECTIVITY_PRIO,
|
||||||
&connectivity_loop_task, WIFI_CORE);
|
&connectivity_loop_task, esp32hal->WIFICORE());
|
||||||
#endif
|
}
|
||||||
|
|
||||||
|
if (!led_init()) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
#if defined(LOG_CAN_TO_SD) || defined(LOG_TO_SD)
|
#if defined(LOG_CAN_TO_SD) || defined(LOG_TO_SD)
|
||||||
xTaskCreatePinnedToCore((TaskFunction_t)&logging_loop, "logging_loop", 4096, NULL, TASK_CONNECTIVITY_PRIO,
|
xTaskCreatePinnedToCore((TaskFunction_t)&logging_loop, "logging_loop", 4096, NULL, TASK_CONNECTIVITY_PRIO,
|
||||||
&logging_loop_task, WIFI_CORE);
|
&logging_loop_task, esp32hal->WIFICORE());
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef PRECHARGE_CONTROL
|
if (!init_contactors()) {
|
||||||
init_precharge_control();
|
return;
|
||||||
#endif // PRECHARGE_CONTROL
|
}
|
||||||
|
|
||||||
|
if (!init_precharge_control()) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
setup_charger();
|
setup_charger();
|
||||||
setup_inverter();
|
|
||||||
|
if (!setup_inverter()) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
setup_battery();
|
setup_battery();
|
||||||
setup_can_shunt();
|
setup_can_shunt();
|
||||||
|
|
||||||
// Init CAN only after any CAN receivers have had a chance to register.
|
// Init CAN only after any CAN receivers have had a chance to register.
|
||||||
init_CAN();
|
if (!init_CAN()) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
init_contactors();
|
if (!init_rs485()) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
init_rs485();
|
if (!init_equipment_stop_button()) {
|
||||||
|
return;
|
||||||
#ifdef EQUIPMENT_STOP_BUTTON
|
}
|
||||||
init_equipment_stop_button();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// BOOT button at runtime is used as an input for various things
|
// BOOT button at runtime is used as an input for various things
|
||||||
pinMode(0, INPUT_PULLUP);
|
pinMode(0, INPUT_PULLUP);
|
||||||
|
@ -117,21 +116,25 @@ void setup() {
|
||||||
// Initialize Task Watchdog for subscribed tasks
|
// Initialize Task Watchdog for subscribed tasks
|
||||||
esp_task_wdt_config_t wdt_config = {
|
esp_task_wdt_config_t wdt_config = {
|
||||||
.timeout_ms = INTERVAL_5_S, // If task hangs for longer than this, reboot
|
.timeout_ms = INTERVAL_5_S, // If task hangs for longer than this, reboot
|
||||||
.idle_core_mask = (1 << CORE_FUNCTION_CORE) | (1 << WIFI_CORE), // Watch both cores
|
.idle_core_mask =
|
||||||
|
(uint32_t)(1 << esp32hal->CORE_FUNCTION_CORE()) | (uint32_t)(1 << esp32hal->WIFICORE()), // Watch both cores
|
||||||
.trigger_panic = true // Enable panic reset on timeout
|
.trigger_panic = true // Enable panic reset on timeout
|
||||||
};
|
};
|
||||||
|
|
||||||
// Start tasks
|
// Start tasks
|
||||||
|
|
||||||
#ifdef MQTT
|
if (mqtt_enabled) {
|
||||||
init_mqtt();
|
if (!init_mqtt()) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
xTaskCreatePinnedToCore((TaskFunction_t)&mqtt_loop, "mqtt_loop", 4096, NULL, TASK_MQTT_PRIO, &mqtt_loop_task,
|
xTaskCreatePinnedToCore((TaskFunction_t)&mqtt_loop, "mqtt_loop", 4096, NULL, TASK_MQTT_PRIO, &mqtt_loop_task,
|
||||||
WIFI_CORE);
|
esp32hal->WIFICORE());
|
||||||
#endif
|
}
|
||||||
|
|
||||||
xTaskCreatePinnedToCore((TaskFunction_t)&core_loop, "core_loop", 4096, NULL, TASK_CORE_PRIO, &main_loop_task,
|
xTaskCreatePinnedToCore((TaskFunction_t)&core_loop, "core_loop", 4096, NULL, TASK_CORE_PRIO, &main_loop_task,
|
||||||
CORE_FUNCTION_CORE);
|
esp32hal->CORE_FUNCTION_CORE());
|
||||||
|
|
||||||
#ifdef PERIODIC_BMS_RESET_AT
|
#ifdef PERIODIC_BMS_RESET_AT
|
||||||
bmsResetTimeOffset = getTimeOffsetfromNowUntil(PERIODIC_BMS_RESET_AT);
|
bmsResetTimeOffset = getTimeOffsetfromNowUntil(PERIODIC_BMS_RESET_AT);
|
||||||
if (bmsResetTimeOffset == 0) {
|
if (bmsResetTimeOffset == 0) {
|
||||||
|
@ -164,35 +167,34 @@ void logging_loop(void*) {
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef WIFI
|
|
||||||
void connectivity_loop(void*) {
|
void connectivity_loop(void*) {
|
||||||
esp_task_wdt_add(NULL); // Register this task with WDT
|
esp_task_wdt_add(NULL); // Register this task with WDT
|
||||||
// Init wifi
|
// Init wifi
|
||||||
init_WiFi();
|
init_WiFi();
|
||||||
|
|
||||||
#ifdef WEBSERVER
|
if (webserver_enabled) {
|
||||||
// Init webserver
|
|
||||||
init_webserver();
|
init_webserver();
|
||||||
#endif
|
}
|
||||||
#ifdef MDNSRESPONDER
|
|
||||||
|
if (mdns_enabled) {
|
||||||
init_mDNS();
|
init_mDNS();
|
||||||
#endif
|
}
|
||||||
|
|
||||||
while (true) {
|
while (true) {
|
||||||
START_TIME_MEASUREMENT(wifi);
|
START_TIME_MEASUREMENT(wifi);
|
||||||
wifi_monitor();
|
wifi_monitor();
|
||||||
#ifdef WEBSERVER
|
|
||||||
|
if (webserver_enabled) {
|
||||||
ota_monitor();
|
ota_monitor();
|
||||||
#endif
|
}
|
||||||
|
|
||||||
END_TIME_MEASUREMENT_MAX(wifi, datalayer.system.status.wifi_task_10s_max_us);
|
END_TIME_MEASUREMENT_MAX(wifi, datalayer.system.status.wifi_task_10s_max_us);
|
||||||
|
|
||||||
esp_task_wdt_reset(); // Reset watchdog
|
esp_task_wdt_reset(); // Reset watchdog
|
||||||
delay(1);
|
delay(1);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef MQTT
|
|
||||||
void mqtt_loop(void*) {
|
void mqtt_loop(void*) {
|
||||||
esp_task_wdt_add(NULL); // Register this task with WDT
|
esp_task_wdt_add(NULL); // Register this task with WDT
|
||||||
|
|
||||||
|
@ -204,7 +206,6 @@ void mqtt_loop(void*) {
|
||||||
delay(1);
|
delay(1);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
static std::list<Transmitter*> transmitters;
|
static std::list<Transmitter*> transmitters;
|
||||||
|
|
||||||
|
@ -217,31 +218,31 @@ void core_loop(void*) {
|
||||||
esp_task_wdt_add(NULL); // Register this task with WDT
|
esp_task_wdt_add(NULL); // Register this task with WDT
|
||||||
TickType_t xLastWakeTime = xTaskGetTickCount();
|
TickType_t xLastWakeTime = xTaskGetTickCount();
|
||||||
const TickType_t xFrequency = pdMS_TO_TICKS(1); // Convert 1ms to ticks
|
const TickType_t xFrequency = pdMS_TO_TICKS(1); // Convert 1ms to ticks
|
||||||
led_init();
|
|
||||||
|
|
||||||
while (true) {
|
while (true) {
|
||||||
|
|
||||||
START_TIME_MEASUREMENT(all);
|
START_TIME_MEASUREMENT(all);
|
||||||
START_TIME_MEASUREMENT(comm);
|
START_TIME_MEASUREMENT(comm);
|
||||||
#ifdef EQUIPMENT_STOP_BUTTON
|
|
||||||
monitor_equipment_stop_button();
|
monitor_equipment_stop_button();
|
||||||
#endif
|
|
||||||
|
|
||||||
// Input, Runs as fast as possible
|
// Input, Runs as fast as possible
|
||||||
receive_can(); // Receive CAN messages
|
receive_can(); // Receive CAN messages
|
||||||
receive_rs485(); // Process serial2 RS485 interface
|
receive_rs485(); // Process serial2 RS485 interface
|
||||||
|
|
||||||
END_TIME_MEASUREMENT_MAX(comm, datalayer.system.status.time_comm_us);
|
END_TIME_MEASUREMENT_MAX(comm, datalayer.system.status.time_comm_us);
|
||||||
#ifdef WEBSERVER
|
|
||||||
|
if (webserver_enabled) {
|
||||||
START_TIME_MEASUREMENT(ota);
|
START_TIME_MEASUREMENT(ota);
|
||||||
ElegantOTA.loop();
|
ElegantOTA.loop();
|
||||||
END_TIME_MEASUREMENT_MAX(ota, datalayer.system.status.time_ota_us);
|
END_TIME_MEASUREMENT_MAX(ota, datalayer.system.status.time_ota_us);
|
||||||
#endif // WEBSERVER
|
}
|
||||||
|
|
||||||
// Process
|
// Process
|
||||||
currentMillis = millis();
|
currentMillis = millis();
|
||||||
if (currentMillis - previousMillis10ms >= INTERVAL_10_MS) {
|
if (currentMillis - previousMillis10ms >= INTERVAL_10_MS) {
|
||||||
if ((currentMillis - previousMillis10ms >= INTERVAL_10_MS_DELAYED) && (currentMillis > BOOTUP_TIME)) {
|
if ((currentMillis - previousMillis10ms >= INTERVAL_10_MS_DELAYED) &&
|
||||||
|
(milliseconds(currentMillis) > esp32hal->BOOTUP_TIME())) {
|
||||||
set_event(EVENT_TASK_OVERRUN, (currentMillis - previousMillis10ms));
|
set_event(EVENT_TASK_OVERRUN, (currentMillis - previousMillis10ms));
|
||||||
}
|
}
|
||||||
previousMillis10ms = currentMillis;
|
previousMillis10ms = currentMillis;
|
||||||
|
|
|
@ -1,5 +1,6 @@
|
||||||
/* This file should be renamed to USER_SECRETS.h to be able to use the software!
|
/* This file should be renamed to USER_SECRETS.h to be able to use the software!
|
||||||
It contains all the credentials that should never be made public */
|
It contains all the credentials that should never be made public */
|
||||||
|
#ifndef COMMON_IMAGE
|
||||||
|
|
||||||
//Password to the access point generated by the Battery-Emulator
|
//Password to the access point generated by the Battery-Emulator
|
||||||
#define AP_PASSWORD "123456789" // Minimum of 8 characters; set to blank if you want the access point to be open
|
#define AP_PASSWORD "123456789" // Minimum of 8 characters; set to blank if you want the access point to be open
|
||||||
|
@ -18,3 +19,4 @@ It contains all the credentials that should never be made public */
|
||||||
#define MQTT_PORT 1883 // MQTT server port
|
#define MQTT_PORT 1883 // MQTT server port
|
||||||
#define MQTT_USER "" // MQTT username, leave blank for no authentication
|
#define MQTT_USER "" // MQTT username, leave blank for no authentication
|
||||||
#define MQTT_PASSWORD "" // MQTT password, leave blank for no authentication
|
#define MQTT_PASSWORD "" // MQTT password, leave blank for no authentication
|
||||||
|
#endif
|
||||||
|
|
|
@ -21,26 +21,40 @@ volatile CAN_Configuration can_config = {
|
||||||
.shunt = CAN_NATIVE // (OPTIONAL) Which CAN is your shunt connected to?
|
.shunt = CAN_NATIVE // (OPTIONAL) Which CAN is your shunt connected to?
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#ifdef COMMON_IMAGE
|
||||||
|
std::string ssid;
|
||||||
|
std::string password;
|
||||||
|
std::string passwordAP;
|
||||||
|
#else
|
||||||
std::string ssid = WIFI_SSID; // Set in USER_SECRETS.h
|
std::string ssid = WIFI_SSID; // Set in USER_SECRETS.h
|
||||||
std::string password = WIFI_PASSWORD; // Set in USER_SECRETS.h
|
std::string password = WIFI_PASSWORD; // Set in USER_SECRETS.h
|
||||||
const char* ssidAP = "Battery Emulator"; // Maximum of 63 characters, also used for device name on web interface
|
std::string passwordAP = AP_PASSWORD; // Set in USER_SECRETS.h
|
||||||
const char* passwordAP = AP_PASSWORD; // Set in USER_SECRETS.h
|
#endif
|
||||||
|
|
||||||
const uint8_t wifi_channel = 0; // Set to 0 for automatic channel selection
|
const uint8_t wifi_channel = 0; // Set to 0 for automatic channel selection
|
||||||
|
|
||||||
#ifdef WEBSERVER
|
#ifdef COMMON_IMAGE
|
||||||
const char* http_username = HTTP_USERNAME; // Set in USER_SECRETS.h
|
std::string http_username;
|
||||||
const char* http_password = HTTP_PASSWORD; // Set in USER_SECRETS.h
|
std::string http_password;
|
||||||
|
#else
|
||||||
|
std::string http_username = HTTP_USERNAME; // Set in USER_SECRETS.h
|
||||||
|
std::string http_password = HTTP_PASSWORD; // Set in USER_SECRETS.h
|
||||||
|
#endif
|
||||||
|
|
||||||
// Set your Static IP address. Only used incase WIFICONFIG is set in USER_SETTINGS.h
|
// Set your Static IP address. Only used incase WIFICONFIG is set in USER_SETTINGS.h
|
||||||
IPAddress local_IP(192, 168, 10, 150);
|
IPAddress local_IP(192, 168, 10, 150);
|
||||||
IPAddress gateway(192, 168, 10, 1);
|
IPAddress gateway(192, 168, 10, 1);
|
||||||
IPAddress subnet(255, 255, 255, 0);
|
IPAddress subnet(255, 255, 255, 0);
|
||||||
#endif // WEBSERVER
|
|
||||||
|
|
||||||
// MQTT
|
// MQTT
|
||||||
#ifdef MQTT
|
#ifdef COMMON_IMAGE
|
||||||
const char* mqtt_user = MQTT_USER; // Set in USER_SECRETS.h
|
std::string mqtt_user;
|
||||||
const char* mqtt_password = MQTT_PASSWORD; // Set in USER_SECRETS.h
|
std::string mqtt_password;
|
||||||
#ifdef MQTT_MANUAL_TOPIC_OBJECT_NAME
|
#else
|
||||||
|
std::string mqtt_user = MQTT_USER; // Set in USER_SECRETS.h
|
||||||
|
std::string mqtt_password = MQTT_PASSWORD; // Set in USER_SECRETS.h
|
||||||
|
#endif
|
||||||
|
|
||||||
const char* mqtt_topic_name =
|
const char* mqtt_topic_name =
|
||||||
"BE"; // Custom MQTT topic name. Previously, the name was automatically set to "battery-emulator_esp32-XXXXXX"
|
"BE"; // Custom MQTT topic name. Previously, the name was automatically set to "battery-emulator_esp32-XXXXXX"
|
||||||
const char* mqtt_object_id_prefix =
|
const char* mqtt_object_id_prefix =
|
||||||
|
@ -49,15 +63,6 @@ const char* mqtt_device_name =
|
||||||
"Battery Emulator"; // Custom device name in Home Assistant. Previously, the name was automatically set to "BatteryEmulator_esp32-XXXXXX"
|
"Battery Emulator"; // Custom device name in Home Assistant. Previously, the name was automatically set to "BatteryEmulator_esp32-XXXXXX"
|
||||||
const char* ha_device_id =
|
const char* ha_device_id =
|
||||||
"battery-emulator"; // Custom device ID in Home Assistant. Previously, the ID was always "battery-emulator"
|
"battery-emulator"; // Custom device ID in Home Assistant. Previously, the ID was always "battery-emulator"
|
||||||
#endif // MQTT_MANUAL_TOPIC_OBJECT_NAME
|
|
||||||
#endif // USE_MQTT
|
|
||||||
|
|
||||||
#ifdef EQUIPMENT_STOP_BUTTON
|
|
||||||
// Equipment stop button behavior. Use NC button for safety reasons.
|
|
||||||
//LATCHING_SWITCH - Normally closed (NC), latching switch. When pressed it activates e-stop
|
|
||||||
//MOMENTARY_SWITCH - Short press to activate e-stop, long 15s press to deactivate. E-stop is persistent between reboots
|
|
||||||
volatile STOP_BUTTON_BEHAVIOR equipment_stop_behavior = LATCHING_SWITCH;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/* Charger settings (Optional, when using generator charging) */
|
/* Charger settings (Optional, when using generator charging) */
|
||||||
volatile float CHARGER_SET_HV = 384; // Reasonably appropriate 4.0v per cell charging of a 96s pack
|
volatile float CHARGER_SET_HV = 384; // Reasonably appropriate 4.0v per cell charging of a 96s pack
|
||||||
|
|
|
@ -197,9 +197,16 @@ extern volatile float CHARGER_END_A;
|
||||||
|
|
||||||
extern volatile unsigned long long bmsResetTimeOffset;
|
extern volatile unsigned long long bmsResetTimeOffset;
|
||||||
|
|
||||||
|
#include "src/communication/equipmentstopbutton/comm_equipmentstopbutton.h"
|
||||||
|
|
||||||
|
// Equipment stop button behavior. Use NC button for safety reasons.
|
||||||
|
//LATCHING_SWITCH - Normally closed (NC), latching switch. When pressed it activates e-stop
|
||||||
|
//MOMENTARY_SWITCH - Short press to activate e-stop, long 15s press to deactivate. E-stop is persistent between reboots
|
||||||
|
|
||||||
#ifdef EQUIPMENT_STOP_BUTTON
|
#ifdef EQUIPMENT_STOP_BUTTON
|
||||||
typedef enum { LATCHING_SWITCH = 0, MOMENTARY_SWITCH = 1 } STOP_BUTTON_BEHAVIOR;
|
const STOP_BUTTON_BEHAVIOR stop_button_default_behavior = STOP_BUTTON_BEHAVIOR::MOMENTARY_SWITCH;
|
||||||
extern volatile STOP_BUTTON_BEHAVIOR equipment_stop_behavior;
|
#else
|
||||||
|
const STOP_BUTTON_BEHAVIOR stop_button_default_behavior = STOP_BUTTON_BEHAVIOR::NOT_CONNECTED;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef WIFICONFIG
|
#ifdef WIFICONFIG
|
||||||
|
|
|
@ -5,13 +5,12 @@
|
||||||
#include "RS485Battery.h"
|
#include "RS485Battery.h"
|
||||||
|
|
||||||
#if !defined(COMMON_IMAGE) && !defined(SELECTED_BATTERY_CLASS)
|
#if !defined(COMMON_IMAGE) && !defined(SELECTED_BATTERY_CLASS)
|
||||||
#error No battery selected! Choose one from the USER_SETTINGS.h file
|
#error No battery selected! Choose one from the USER_SETTINGS.h file or build COMMON_IMAGE.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
Battery* battery = nullptr;
|
Battery* battery = nullptr;
|
||||||
Battery* battery2 = nullptr;
|
Battery* battery2 = nullptr;
|
||||||
|
|
||||||
#ifdef COMMON_IMAGE
|
|
||||||
std::vector<BatteryType> supported_battery_types() {
|
std::vector<BatteryType> supported_battery_types() {
|
||||||
std::vector<BatteryType> types;
|
std::vector<BatteryType> types;
|
||||||
|
|
||||||
|
@ -22,7 +21,39 @@ std::vector<BatteryType> supported_battery_types() {
|
||||||
return types;
|
return types;
|
||||||
}
|
}
|
||||||
|
|
||||||
extern const char* name_for_battery_type(BatteryType type) {
|
const char* name_for_chemistry(battery_chemistry_enum chem) {
|
||||||
|
switch (chem) {
|
||||||
|
case battery_chemistry_enum::LFP:
|
||||||
|
return "LFP";
|
||||||
|
case battery_chemistry_enum::NCA:
|
||||||
|
return "NCA";
|
||||||
|
case battery_chemistry_enum::NMC:
|
||||||
|
return "NMC";
|
||||||
|
default:
|
||||||
|
return nullptr;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
const char* name_for_comm_interface(comm_interface comm) {
|
||||||
|
switch (comm) {
|
||||||
|
case comm_interface::Modbus:
|
||||||
|
return "Modbus";
|
||||||
|
case comm_interface::RS485:
|
||||||
|
return "RS485";
|
||||||
|
case comm_interface::CanNative:
|
||||||
|
return "Native CAN";
|
||||||
|
case comm_interface::CanFdNative:
|
||||||
|
return "Native CAN FD";
|
||||||
|
case comm_interface::CanAddonMcp2515:
|
||||||
|
return "CAN MCP 2515 add-on";
|
||||||
|
case comm_interface::CanFdAddonMcp2518:
|
||||||
|
return "CAN FD MCP 2518 add-on";
|
||||||
|
default:
|
||||||
|
return nullptr;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
const char* name_for_battery_type(BatteryType type) {
|
||||||
switch (type) {
|
switch (type) {
|
||||||
case BatteryType::None:
|
case BatteryType::None:
|
||||||
return "None";
|
return "None";
|
||||||
|
@ -36,10 +67,8 @@ extern const char* name_for_battery_type(BatteryType type) {
|
||||||
return BydAttoBattery::Name;
|
return BydAttoBattery::Name;
|
||||||
case BatteryType::CellPowerBms:
|
case BatteryType::CellPowerBms:
|
||||||
return CellPowerBms::Name;
|
return CellPowerBms::Name;
|
||||||
#ifdef CHADEMO_PIN_2 // Only support chademo for certain platforms
|
|
||||||
case BatteryType::Chademo:
|
case BatteryType::Chademo:
|
||||||
return ChademoBattery::Name;
|
return ChademoBattery::Name;
|
||||||
#endif
|
|
||||||
case BatteryType::CmfaEv:
|
case BatteryType::CmfaEv:
|
||||||
return CmfaEvBattery::Name;
|
return CmfaEvBattery::Name;
|
||||||
case BatteryType::Foxess:
|
case BatteryType::Foxess:
|
||||||
|
@ -102,8 +131,15 @@ extern const char* name_for_battery_type(BatteryType type) {
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#ifdef LFP_CHEMISTRY
|
||||||
|
const battery_chemistry_enum battery_chemistry_default = battery_chemistry_enum::LFP;
|
||||||
|
#else
|
||||||
|
const battery_chemistry_enum battery_chemistry_default = battery_chemistry_enum::NMC;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
battery_chemistry_enum user_selected_battery_chemistry = battery_chemistry_default;
|
||||||
|
|
||||||
#ifdef COMMON_IMAGE
|
#ifdef COMMON_IMAGE
|
||||||
#ifdef SELECTED_BATTERY_CLASS
|
#ifdef SELECTED_BATTERY_CLASS
|
||||||
#error "Compile time SELECTED_BATTERY_CLASS should not be defined with COMMON_IMAGE"
|
#error "Compile time SELECTED_BATTERY_CLASS should not be defined with COMMON_IMAGE"
|
||||||
|
@ -126,10 +162,8 @@ Battery* create_battery(BatteryType type) {
|
||||||
return new BydAttoBattery();
|
return new BydAttoBattery();
|
||||||
case BatteryType::CellPowerBms:
|
case BatteryType::CellPowerBms:
|
||||||
return new CellPowerBms();
|
return new CellPowerBms();
|
||||||
#ifdef CHADEMO_PIN_2 // Only support chademo for certain platforms
|
|
||||||
case BatteryType::Chademo:
|
case BatteryType::Chademo:
|
||||||
return new ChademoBattery();
|
return new ChademoBattery();
|
||||||
#endif
|
|
||||||
case BatteryType::CmfaEv:
|
case BatteryType::CmfaEv:
|
||||||
return new CmfaEvBattery();
|
return new CmfaEvBattery();
|
||||||
case BatteryType::Foxess:
|
case BatteryType::Foxess:
|
||||||
|
@ -179,7 +213,7 @@ Battery* create_battery(BatteryType type) {
|
||||||
case BatteryType::SimpBms:
|
case BatteryType::SimpBms:
|
||||||
return new SimpBmsBattery();
|
return new SimpBmsBattery();
|
||||||
case BatteryType::TeslaModel3Y:
|
case BatteryType::TeslaModel3Y:
|
||||||
return new TeslaModel3YBattery();
|
return new TeslaModel3YBattery(user_selected_battery_chemistry);
|
||||||
case BatteryType::TeslaModelSX:
|
case BatteryType::TeslaModelSX:
|
||||||
return new TeslaModelSXBattery();
|
return new TeslaModelSXBattery();
|
||||||
case BatteryType::TestFake:
|
case BatteryType::TestFake:
|
||||||
|
@ -212,7 +246,7 @@ void setup_battery() {
|
||||||
break;
|
break;
|
||||||
case BatteryType::BmwI3:
|
case BatteryType::BmwI3:
|
||||||
battery2 = new BmwI3Battery(&datalayer.battery2, &datalayer.system.status.battery2_allowed_contactor_closing,
|
battery2 = new BmwI3Battery(&datalayer.battery2, &datalayer.system.status.battery2_allowed_contactor_closing,
|
||||||
can_config.battery_double, WUP_PIN2);
|
can_config.battery_double, esp32hal->WUP_PIN2());
|
||||||
break;
|
break;
|
||||||
case BatteryType::KiaHyundai64:
|
case BatteryType::KiaHyundai64:
|
||||||
battery2 = new KiaHyundai64Battery(&datalayer.battery2, &datalayer_extended.KiaHyundai64_2,
|
battery2 = new KiaHyundai64Battery(&datalayer.battery2, &datalayer_extended.KiaHyundai64_2,
|
||||||
|
@ -221,6 +255,9 @@ void setup_battery() {
|
||||||
case BatteryType::SantaFePhev:
|
case BatteryType::SantaFePhev:
|
||||||
battery2 = new SantaFePhevBattery(&datalayer.battery2, can_config.battery_double);
|
battery2 = new SantaFePhevBattery(&datalayer.battery2, can_config.battery_double);
|
||||||
break;
|
break;
|
||||||
|
case BatteryType::RenaultZoe1:
|
||||||
|
battery2 = new RenaultZoeGen1Battery(&datalayer.battery2, nullptr, can_config.battery_double);
|
||||||
|
break;
|
||||||
case BatteryType::TestFake:
|
case BatteryType::TestFake:
|
||||||
battery2 = new TestFakeBattery(&datalayer.battery2, can_config.battery_double);
|
battery2 = new TestFakeBattery(&datalayer.battery2, can_config.battery_double);
|
||||||
break;
|
break;
|
||||||
|
@ -236,7 +273,11 @@ void setup_battery() {
|
||||||
void setup_battery() {
|
void setup_battery() {
|
||||||
// Instantiate the battery only once just in case this function gets called multiple times.
|
// Instantiate the battery only once just in case this function gets called multiple times.
|
||||||
if (battery == nullptr) {
|
if (battery == nullptr) {
|
||||||
|
#ifdef TESLA_MODEL_3Y_BATTERY
|
||||||
|
battery = new SELECTED_BATTERY_CLASS(user_selected_battery_chemistry);
|
||||||
|
#else
|
||||||
battery = new SELECTED_BATTERY_CLASS();
|
battery = new SELECTED_BATTERY_CLASS();
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
battery->setup();
|
battery->setup();
|
||||||
|
|
||||||
|
@ -245,7 +286,7 @@ void setup_battery() {
|
||||||
#if defined(BMW_I3_BATTERY)
|
#if defined(BMW_I3_BATTERY)
|
||||||
battery2 =
|
battery2 =
|
||||||
new SELECTED_BATTERY_CLASS(&datalayer.battery2, &datalayer.system.status.battery2_allowed_contactor_closing,
|
new SELECTED_BATTERY_CLASS(&datalayer.battery2, &datalayer.system.status.battery2_allowed_contactor_closing,
|
||||||
can_config.battery_double, WUP_PIN2);
|
can_config.battery_double, esp32hal->WUP_PIN2());
|
||||||
#elif defined(KIA_HYUNDAI_64_BATTERY)
|
#elif defined(KIA_HYUNDAI_64_BATTERY)
|
||||||
battery2 = new SELECTED_BATTERY_CLASS(&datalayer.battery2, &datalayer_extended.KiaHyundai64_2,
|
battery2 = new SELECTED_BATTERY_CLASS(&datalayer.battery2, &datalayer_extended.KiaHyundai64_2,
|
||||||
&datalayer.system.status.battery2_allowed_contactor_closing,
|
&datalayer.system.status.battery2_allowed_contactor_closing,
|
||||||
|
|
|
@ -493,6 +493,10 @@ void BmwI3Battery::transmit_can(unsigned long currentMillis) {
|
||||||
}
|
}
|
||||||
|
|
||||||
void BmwI3Battery::setup(void) { // Performs one time setup at startup
|
void BmwI3Battery::setup(void) { // Performs one time setup at startup
|
||||||
|
if (!esp32hal->alloc_pins(Name, wakeup_pin)) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
strncpy(datalayer.system.info.battery_protocol, Name, 63);
|
strncpy(datalayer.system.info.battery_protocol, Name, 63);
|
||||||
datalayer.system.info.battery_protocol[63] = '\0';
|
datalayer.system.info.battery_protocol[63] = '\0';
|
||||||
|
|
||||||
|
|
|
@ -14,7 +14,7 @@ class BmwI3Battery : public CanBattery {
|
||||||
public:
|
public:
|
||||||
// Use this constructor for the second battery.
|
// Use this constructor for the second battery.
|
||||||
BmwI3Battery(DATALAYER_BATTERY_TYPE* datalayer_ptr, bool* contactor_closing_allowed_ptr, CAN_Interface targetCan,
|
BmwI3Battery(DATALAYER_BATTERY_TYPE* datalayer_ptr, bool* contactor_closing_allowed_ptr, CAN_Interface targetCan,
|
||||||
int wakeup)
|
gpio_num_t wakeup)
|
||||||
: CanBattery(targetCan), renderer(*this) {
|
: CanBattery(targetCan), renderer(*this) {
|
||||||
datalayer_battery = datalayer_ptr;
|
datalayer_battery = datalayer_ptr;
|
||||||
contactor_closing_allowed = contactor_closing_allowed_ptr;
|
contactor_closing_allowed = contactor_closing_allowed_ptr;
|
||||||
|
@ -30,7 +30,7 @@ class BmwI3Battery : public CanBattery {
|
||||||
datalayer_battery = &datalayer.battery;
|
datalayer_battery = &datalayer.battery;
|
||||||
allows_contactor_closing = &datalayer.system.status.battery_allows_contactor_closing;
|
allows_contactor_closing = &datalayer.system.status.battery_allows_contactor_closing;
|
||||||
contactor_closing_allowed = nullptr;
|
contactor_closing_allowed = nullptr;
|
||||||
wakeup_pin = WUP_PIN1;
|
wakeup_pin = esp32hal->WUP_PIN1();
|
||||||
}
|
}
|
||||||
|
|
||||||
virtual void setup(void);
|
virtual void setup(void);
|
||||||
|
@ -95,7 +95,7 @@ class BmwI3Battery : public CanBattery {
|
||||||
// If not null, this battery listens to this boolean to determine whether contactor closing is allowed
|
// If not null, this battery listens to this boolean to determine whether contactor closing is allowed
|
||||||
bool* contactor_closing_allowed;
|
bool* contactor_closing_allowed;
|
||||||
|
|
||||||
int wakeup_pin;
|
gpio_num_t wakeup_pin;
|
||||||
|
|
||||||
unsigned long previousMillis20 = 0; // will store last time a 20ms CAN Message was send
|
unsigned long previousMillis20 = 0; // will store last time a 20ms CAN Message was send
|
||||||
unsigned long previousMillis100 = 0; // will store last time a 100ms CAN Message was send
|
unsigned long previousMillis100 = 0; // will store last time a 100ms CAN Message was send
|
||||||
|
|
|
@ -188,12 +188,12 @@ void BmwPhevBattery::wake_battery_via_canbus() {
|
||||||
// Followed by a Recessive interval of at least ~3 µs (min) and at most ~10 µs (max)
|
// Followed by a Recessive interval of at least ~3 µs (min) and at most ~10 µs (max)
|
||||||
// Then a second dominant pulse of similar timing.
|
// Then a second dominant pulse of similar timing.
|
||||||
|
|
||||||
CAN_cfg.speed = CAN_SPEED_100KBPS; //Slow down canbus to achieve wakeup timings
|
auto original_speed = change_can_speed(CAN_Speed::CAN_SPEED_100KBPS);
|
||||||
ESP32Can.CANInit(); // ReInit native CAN module at new speed
|
|
||||||
transmit_can_frame(&BMW_PHEV_BUS_WAKEUP_REQUEST, can_config.battery);
|
transmit_can_frame(&BMW_PHEV_BUS_WAKEUP_REQUEST, can_config.battery);
|
||||||
transmit_can_frame(&BMW_PHEV_BUS_WAKEUP_REQUEST, can_config.battery);
|
transmit_can_frame(&BMW_PHEV_BUS_WAKEUP_REQUEST, can_config.battery);
|
||||||
CAN_cfg.speed = CAN_SPEED_500KBPS; //Resume fullspeed
|
|
||||||
ESP32Can.CANInit(); // ReInit native CAN module at new speed
|
change_can_speed(original_speed);
|
||||||
|
|
||||||
#ifdef DEBUG_LOG
|
#ifdef DEBUG_LOG
|
||||||
logging.println("Sent magic wakeup packet to SME at 100kbps...");
|
logging.println("Sent magic wakeup packet to SME at 100kbps...");
|
||||||
|
|
|
@ -2,11 +2,11 @@
|
||||||
#define BATTERY_H
|
#define BATTERY_H
|
||||||
|
|
||||||
#include <vector>
|
#include <vector>
|
||||||
|
#include "src/devboard/utils/types.h"
|
||||||
#include "src/devboard/webserver/BatteryHtmlRenderer.h"
|
#include "src/devboard/webserver/BatteryHtmlRenderer.h"
|
||||||
|
|
||||||
enum class BatteryType {
|
enum class BatteryType {
|
||||||
None = 0,
|
None = 0,
|
||||||
BmwSbox = 1,
|
|
||||||
BmwI3 = 2,
|
BmwI3 = 2,
|
||||||
BmwIx = 3,
|
BmwIx = 3,
|
||||||
BoltAmpera = 4,
|
BoltAmpera = 4,
|
||||||
|
@ -48,10 +48,14 @@ enum class BatteryType {
|
||||||
|
|
||||||
extern std::vector<BatteryType> supported_battery_types();
|
extern std::vector<BatteryType> supported_battery_types();
|
||||||
extern const char* name_for_battery_type(BatteryType type);
|
extern const char* name_for_battery_type(BatteryType type);
|
||||||
|
extern const char* name_for_chemistry(battery_chemistry_enum chem);
|
||||||
|
extern const char* name_for_comm_interface(comm_interface comm);
|
||||||
|
|
||||||
extern BatteryType user_selected_battery_type;
|
extern BatteryType user_selected_battery_type;
|
||||||
extern bool user_selected_second_battery;
|
extern bool user_selected_second_battery;
|
||||||
|
|
||||||
|
extern battery_chemistry_enum user_selected_battery_chemistry;
|
||||||
|
|
||||||
// Abstract base class for next-generation battery implementations.
|
// Abstract base class for next-generation battery implementations.
|
||||||
// Defines the interface to call battery specific functionality.
|
// Defines the interface to call battery specific functionality.
|
||||||
class Battery {
|
class Battery {
|
||||||
|
|
|
@ -11,7 +11,7 @@
|
||||||
|
|
||||||
class CellPowerBms : public CanBattery {
|
class CellPowerBms : public CanBattery {
|
||||||
public:
|
public:
|
||||||
CellPowerBms() : CanBattery(true) {}
|
CellPowerBms() : CanBattery(CAN_Speed::CAN_SPEED_250KBPS) {}
|
||||||
|
|
||||||
virtual void setup(void);
|
virtual void setup(void);
|
||||||
virtual void handle_incoming_can_frame(CAN_frame rx_frame);
|
virtual void handle_incoming_can_frame(CAN_frame rx_frame);
|
||||||
|
|
|
@ -4,8 +4,6 @@
|
||||||
#include "../include.h"
|
#include "../include.h"
|
||||||
#include "CHADEMO-SHUNTS.h"
|
#include "CHADEMO-SHUNTS.h"
|
||||||
|
|
||||||
#ifdef CHADEMO_PIN_2 // Only support chademo for certain platforms
|
|
||||||
|
|
||||||
//This function maps all the values fetched via CAN to the correct parameters used for the inverter
|
//This function maps all the values fetched via CAN to the correct parameters used for the inverter
|
||||||
void ChademoBattery::update_values() {
|
void ChademoBattery::update_values() {
|
||||||
|
|
||||||
|
@ -93,7 +91,7 @@ void ChademoBattery::process_vehicle_charging_session(CAN_frame rx_frame) {
|
||||||
|
|
||||||
vehicle_can_initialized = true;
|
vehicle_can_initialized = true;
|
||||||
|
|
||||||
vehicle_permission = digitalRead(CHADEMO_PIN_4);
|
vehicle_permission = digitalRead(pin4);
|
||||||
|
|
||||||
x102_chg_session.ControlProtocolNumberEV = rx_frame.data.u8[0];
|
x102_chg_session.ControlProtocolNumberEV = rx_frame.data.u8[0];
|
||||||
|
|
||||||
|
@ -650,10 +648,11 @@ void ChademoBattery::transmit_can(unsigned long currentMillis) {
|
||||||
*/
|
*/
|
||||||
void ChademoBattery::handle_chademo_sequence() {
|
void ChademoBattery::handle_chademo_sequence() {
|
||||||
|
|
||||||
precharge_low = digitalRead(PRECHARGE_PIN) == LOW;
|
precharge_low = digitalRead(precharge) == LOW;
|
||||||
positive_high = digitalRead(POSITIVE_CONTACTOR_PIN) == HIGH;
|
positive_high = digitalRead(positive_contactor) == HIGH;
|
||||||
contactors_ready = precharge_low && positive_high;
|
contactors_ready = precharge_low && positive_high;
|
||||||
vehicle_permission = digitalRead(CHADEMO_PIN_4);
|
|
||||||
|
vehicle_permission = digitalRead(pin4);
|
||||||
|
|
||||||
/* ------------------- State override conditions checks ------------------- */
|
/* ------------------- State override conditions checks ------------------- */
|
||||||
/* ------------------------------------------------------------------------------ */
|
/* ------------------------------------------------------------------------------ */
|
||||||
|
@ -676,8 +675,8 @@ void ChademoBattery::handle_chademo_sequence() {
|
||||||
switch (CHADEMO_Status) {
|
switch (CHADEMO_Status) {
|
||||||
case CHADEMO_IDLE:
|
case CHADEMO_IDLE:
|
||||||
/* this is where we can unlock connector */
|
/* this is where we can unlock connector */
|
||||||
digitalWrite(CHADEMO_LOCK, LOW);
|
digitalWrite(pin_lock, LOW);
|
||||||
plug_inserted = digitalRead(CHADEMO_PIN_7);
|
plug_inserted = digitalRead(pin7);
|
||||||
|
|
||||||
if (!plug_inserted) {
|
if (!plug_inserted) {
|
||||||
#ifdef DEBUG_LOG
|
#ifdef DEBUG_LOG
|
||||||
|
@ -704,7 +703,7 @@ void ChademoBattery::handle_chademo_sequence() {
|
||||||
/* If connection is detectable, jumpstart handshake by
|
/* If connection is detectable, jumpstart handshake by
|
||||||
* indicate that the EVSE is ready to begin
|
* indicate that the EVSE is ready to begin
|
||||||
*/
|
*/
|
||||||
digitalWrite(CHADEMO_PIN_2, HIGH);
|
digitalWrite(pin2, HIGH);
|
||||||
|
|
||||||
/* State change to initializing. We will re-enter the handler upon receipt of CAN */
|
/* State change to initializing. We will re-enter the handler upon receipt of CAN */
|
||||||
CHADEMO_Status = CHADEMO_INIT;
|
CHADEMO_Status = CHADEMO_INIT;
|
||||||
|
@ -715,9 +714,7 @@ void ChademoBattery::handle_chademo_sequence() {
|
||||||
* with timers to have higher confidence of certain conditions hitting
|
* with timers to have higher confidence of certain conditions hitting
|
||||||
* a steady state
|
* a steady state
|
||||||
*/
|
*/
|
||||||
#ifdef DEBUG_LOG
|
DEBUG_PRINTLN("CHADEMO plug is not inserted, cannot connect d2 relay to begin initialization.");
|
||||||
logging.println("CHADEMO plug is not inserted, cannot connect d2 relay to begin initialization.");
|
|
||||||
#endif
|
|
||||||
CHADEMO_Status = CHADEMO_IDLE;
|
CHADEMO_Status = CHADEMO_IDLE;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
@ -726,9 +723,7 @@ void ChademoBattery::handle_chademo_sequence() {
|
||||||
* Used for triggers/error handling elsewhere;
|
* Used for triggers/error handling elsewhere;
|
||||||
* State change to CHADEMO_NEGOTIATE occurs in handle_incoming_can_frame_battery(..)
|
* State change to CHADEMO_NEGOTIATE occurs in handle_incoming_can_frame_battery(..)
|
||||||
*/
|
*/
|
||||||
#ifdef DEBUG_LOG
|
DEBUG_PRINTLN("Awaiting initial vehicle CAN to trigger negotiation");
|
||||||
// logging.println("Awaiting initial vehicle CAN to trigger negotiation");
|
|
||||||
#endif
|
|
||||||
evse_init();
|
evse_init();
|
||||||
break;
|
break;
|
||||||
case CHADEMO_NEGOTIATE:
|
case CHADEMO_NEGOTIATE:
|
||||||
|
@ -750,7 +745,7 @@ void ChademoBattery::handle_chademo_sequence() {
|
||||||
// that pin 4 (j) reads high
|
// that pin 4 (j) reads high
|
||||||
if (vehicle_permission) {
|
if (vehicle_permission) {
|
||||||
//lock connector here
|
//lock connector here
|
||||||
digitalWrite(CHADEMO_LOCK, HIGH);
|
digitalWrite(pin_lock, HIGH);
|
||||||
|
|
||||||
//TODO spec requires test to validate solenoid has indeed engaged.
|
//TODO spec requires test to validate solenoid has indeed engaged.
|
||||||
// example uses a comparator/current consumption check around solenoid
|
// example uses a comparator/current consumption check around solenoid
|
||||||
|
@ -780,7 +775,7 @@ void ChademoBattery::handle_chademo_sequence() {
|
||||||
if (x102_chg_session.s.status.StatusVehicleChargingEnabled) {
|
if (x102_chg_session.s.status.StatusVehicleChargingEnabled) {
|
||||||
if (get_measured_voltage() < 20) {
|
if (get_measured_voltage() < 20) {
|
||||||
|
|
||||||
digitalWrite(CHADEMO_PIN_10, HIGH);
|
digitalWrite(pin10, HIGH);
|
||||||
evse_permission = true;
|
evse_permission = true;
|
||||||
} else {
|
} else {
|
||||||
logging.println("Insulation check measures > 20v ");
|
logging.println("Insulation check measures > 20v ");
|
||||||
|
@ -898,8 +893,8 @@ void ChademoBattery::handle_chademo_sequence() {
|
||||||
*/
|
*/
|
||||||
if (get_measured_current() <= 5 && get_measured_voltage() <= 10) {
|
if (get_measured_current() <= 5 && get_measured_voltage() <= 10) {
|
||||||
/* welding detection ideally here */
|
/* welding detection ideally here */
|
||||||
digitalWrite(CHADEMO_PIN_10, LOW);
|
digitalWrite(pin10, LOW);
|
||||||
digitalWrite(CHADEMO_PIN_2, LOW);
|
digitalWrite(pin2, LOW);
|
||||||
CHADEMO_Status = CHADEMO_IDLE;
|
CHADEMO_Status = CHADEMO_IDLE;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -916,8 +911,8 @@ void ChademoBattery::handle_chademo_sequence() {
|
||||||
#ifdef DEBUG_LOG
|
#ifdef DEBUG_LOG
|
||||||
logging.println("CHADEMO fault encountered, tearing down to make safe");
|
logging.println("CHADEMO fault encountered, tearing down to make safe");
|
||||||
#endif
|
#endif
|
||||||
digitalWrite(CHADEMO_PIN_10, LOW);
|
digitalWrite(pin10, LOW);
|
||||||
digitalWrite(CHADEMO_PIN_2, LOW);
|
digitalWrite(pin2, LOW);
|
||||||
evse_permission = false;
|
evse_permission = false;
|
||||||
vehicle_permission = false;
|
vehicle_permission = false;
|
||||||
x209_sent = false;
|
x209_sent = false;
|
||||||
|
@ -937,14 +932,18 @@ void ChademoBattery::handle_chademo_sequence() {
|
||||||
|
|
||||||
void ChademoBattery::setup(void) { // Performs one time setup at startup
|
void ChademoBattery::setup(void) { // Performs one time setup at startup
|
||||||
|
|
||||||
pinMode(CHADEMO_PIN_2, OUTPUT);
|
if (!esp32hal->alloc_pins(Name, pin2, pin10, pin4, pin7, pin_lock)) {
|
||||||
digitalWrite(CHADEMO_PIN_2, LOW);
|
return;
|
||||||
pinMode(CHADEMO_PIN_10, OUTPUT);
|
}
|
||||||
digitalWrite(CHADEMO_PIN_10, LOW);
|
|
||||||
pinMode(CHADEMO_LOCK, OUTPUT);
|
pinMode(pin2, OUTPUT);
|
||||||
digitalWrite(CHADEMO_LOCK, LOW);
|
digitalWrite(pin2, LOW);
|
||||||
pinMode(CHADEMO_PIN_4, INPUT);
|
pinMode(pin10, OUTPUT);
|
||||||
pinMode(CHADEMO_PIN_7, INPUT);
|
digitalWrite(pin10, LOW);
|
||||||
|
pinMode(pin_lock, OUTPUT);
|
||||||
|
digitalWrite(pin_lock, LOW);
|
||||||
|
pinMode(pin4, INPUT);
|
||||||
|
pinMode(pin7, INPUT);
|
||||||
|
|
||||||
strncpy(datalayer.system.info.battery_protocol, Name, 63);
|
strncpy(datalayer.system.info.battery_protocol, Name, 63);
|
||||||
datalayer.system.info.battery_protocol[63] = '\0';
|
datalayer.system.info.battery_protocol[63] = '\0';
|
||||||
|
@ -995,5 +994,3 @@ void ChademoBattery::setup(void) { // Performs one time setup at startup
|
||||||
|
|
||||||
setupMillis = millis();
|
setupMillis = millis();
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
|
||||||
|
|
|
@ -16,6 +16,18 @@
|
||||||
|
|
||||||
class ChademoBattery : public CanBattery {
|
class ChademoBattery : public CanBattery {
|
||||||
public:
|
public:
|
||||||
|
ChademoBattery() {
|
||||||
|
pin2 = esp32hal->CHADEMO_PIN_2();
|
||||||
|
pin10 = esp32hal->CHADEMO_PIN_10();
|
||||||
|
pin4 = esp32hal->CHADEMO_PIN_4();
|
||||||
|
pin7 = esp32hal->CHADEMO_PIN_7();
|
||||||
|
pin_lock = esp32hal->CHADEMO_LOCK();
|
||||||
|
|
||||||
|
// Assuming these are initialized by contactor control module.
|
||||||
|
precharge = esp32hal->PRECHARGE_PIN();
|
||||||
|
positive_contactor = esp32hal->POSITIVE_CONTACTOR_PIN();
|
||||||
|
}
|
||||||
|
|
||||||
virtual void setup(void);
|
virtual void setup(void);
|
||||||
virtual void handle_incoming_can_frame(CAN_frame rx_frame);
|
virtual void handle_incoming_can_frame(CAN_frame rx_frame);
|
||||||
virtual void update_values();
|
virtual void update_values();
|
||||||
|
@ -31,6 +43,7 @@ class ChademoBattery : public CanBattery {
|
||||||
static constexpr const char* Name = "Chademo V2X mode";
|
static constexpr const char* Name = "Chademo V2X mode";
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
gpio_num_t pin2, pin10, pin4, pin7, pin_lock, precharge, positive_contactor;
|
||||||
ChademoBatteryHtmlRenderer renderer;
|
ChademoBatteryHtmlRenderer renderer;
|
||||||
|
|
||||||
void process_vehicle_charging_minimums(CAN_frame rx_frame);
|
void process_vehicle_charging_minimums(CAN_frame rx_frame);
|
||||||
|
|
|
@ -1,8 +1,12 @@
|
||||||
#include "CanBattery.h"
|
#include "CanBattery.h"
|
||||||
#include "../../src/include.h"
|
#include "../../src/include.h"
|
||||||
|
|
||||||
CanBattery::CanBattery(bool halfSpeed) {
|
CanBattery::CanBattery(CAN_Speed speed) {
|
||||||
can_interface = can_config.battery;
|
can_interface = can_config.battery;
|
||||||
register_transmitter(this);
|
register_transmitter(this);
|
||||||
register_can_receiver(this, can_interface, halfSpeed);
|
register_can_receiver(this, can_interface, speed);
|
||||||
|
}
|
||||||
|
|
||||||
|
CAN_Speed CanBattery::change_can_speed(CAN_Speed speed) {
|
||||||
|
return ::change_can_speed(can_interface, speed);
|
||||||
}
|
}
|
||||||
|
|
|
@ -5,6 +5,7 @@
|
||||||
|
|
||||||
#include "src/communication/Transmitter.h"
|
#include "src/communication/Transmitter.h"
|
||||||
#include "src/communication/can/CanReceiver.h"
|
#include "src/communication/can/CanReceiver.h"
|
||||||
|
#include "src/communication/can/comm_can.h"
|
||||||
#include "src/devboard/utils/types.h"
|
#include "src/devboard/utils/types.h"
|
||||||
|
|
||||||
// Abstract base class for batteries using the CAN bus
|
// Abstract base class for batteries using the CAN bus
|
||||||
|
@ -22,13 +23,15 @@ class CanBattery : public Battery, Transmitter, CanReceiver {
|
||||||
protected:
|
protected:
|
||||||
CAN_Interface can_interface;
|
CAN_Interface can_interface;
|
||||||
|
|
||||||
CanBattery(bool halfSpeed = false);
|
CanBattery(CAN_Speed speed = CAN_Speed::CAN_SPEED_500KBPS);
|
||||||
|
|
||||||
CanBattery(CAN_Interface interface, bool halfSpeed = false) {
|
CanBattery(CAN_Interface interface, CAN_Speed speed = CAN_Speed::CAN_SPEED_500KBPS) {
|
||||||
can_interface = interface;
|
can_interface = interface;
|
||||||
register_transmitter(this);
|
register_transmitter(this);
|
||||||
register_can_receiver(this, can_interface, halfSpeed);
|
register_can_receiver(this, can_interface, speed);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
CAN_Speed change_can_speed(CAN_Speed speed);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -70,7 +70,14 @@ void DalyBms::setup(void) { // Performs one time setup at startup
|
||||||
datalayer.battery.info.total_capacity_Wh = BATTERY_WH_MAX;
|
datalayer.battery.info.total_capacity_Wh = BATTERY_WH_MAX;
|
||||||
datalayer.system.status.battery_allows_contactor_closing = true;
|
datalayer.system.status.battery_allows_contactor_closing = true;
|
||||||
|
|
||||||
Serial2.begin(baud_rate(), SERIAL_8N1, RS485_RX_PIN, RS485_TX_PIN);
|
auto rx_pin = esp32hal->RS485_RX_PIN();
|
||||||
|
auto tx_pin = esp32hal->RS485_TX_PIN();
|
||||||
|
|
||||||
|
if (!esp32hal->alloc_pins(Name, rx_pin, tx_pin)) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
Serial2.begin(baud_rate(), SERIAL_8N1, rx_pin, tx_pin);
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t calculate_checksum(uint8_t buff[12]) {
|
uint8_t calculate_checksum(uint8_t buff[12]) {
|
||||||
|
|
|
@ -56,7 +56,7 @@ CAN_frame ipace_keep_alive = {.FD = false,
|
||||||
.ID = 0x59e,
|
.ID = 0x59e,
|
||||||
.data = {0x9E, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF}};*/
|
.data = {0x9E, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF}};*/
|
||||||
|
|
||||||
static void print_units(char* header, int value, char* units) {
|
static void print_units(const char* header, int value, const char* units) {
|
||||||
logging.print(header);
|
logging.print(header);
|
||||||
logging.print(value);
|
logging.print(value);
|
||||||
logging.print(units);
|
logging.print(units);
|
||||||
|
@ -226,7 +226,7 @@ void JaguarIpaceBattery::transmit_can(unsigned long currentMillis) {
|
||||||
}
|
}
|
||||||
|
|
||||||
void JaguarIpaceBattery::setup(void) { // Performs one time setup at startup
|
void JaguarIpaceBattery::setup(void) { // Performs one time setup at startup
|
||||||
strncpy(datalayer.system.info.battery_protocol, "Jaguar I-PACE", 63);
|
strncpy(datalayer.system.info.battery_protocol, Name, 63);
|
||||||
datalayer.system.info.battery_protocol[63] = '\0';
|
datalayer.system.info.battery_protocol[63] = '\0';
|
||||||
datalayer.battery.info.number_of_cells = 108;
|
datalayer.battery.info.number_of_cells = 108;
|
||||||
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
||||||
|
|
|
@ -3,7 +3,6 @@
|
||||||
#include "../datalayer/datalayer.h"
|
#include "../datalayer/datalayer.h"
|
||||||
#include "../devboard/utils/events.h"
|
#include "../devboard/utils/events.h"
|
||||||
#include "../include.h"
|
#include "../include.h"
|
||||||
#include "../lib/pierremolinaro-ACAN2517FD/ACAN2517FD.h"
|
|
||||||
|
|
||||||
const unsigned char crc8_table[256] =
|
const unsigned char crc8_table[256] =
|
||||||
{ // CRC8_SAE_J1850_ZER0 formula,0x1D Poly,initial value 0x3F,Final XOR value varies
|
{ // CRC8_SAE_J1850_ZER0 formula,0x1D Poly,initial value 0x3F,Final XOR value varies
|
||||||
|
|
|
@ -2,11 +2,8 @@
|
||||||
#define KIA_E_GMP_BATTERY_H
|
#define KIA_E_GMP_BATTERY_H
|
||||||
#include <Arduino.h>
|
#include <Arduino.h>
|
||||||
#include "../include.h"
|
#include "../include.h"
|
||||||
#include "../lib/pierremolinaro-ACAN2517FD/ACAN2517FD.h"
|
|
||||||
#include "CanBattery.h"
|
#include "CanBattery.h"
|
||||||
|
|
||||||
extern ACAN2517FD canfd;
|
|
||||||
|
|
||||||
#define ESTIMATE_SOC_FROM_CELLVOLTAGE
|
#define ESTIMATE_SOC_FROM_CELLVOLTAGE
|
||||||
|
|
||||||
#ifdef KIA_E_GMP_BATTERY
|
#ifdef KIA_E_GMP_BATTERY
|
||||||
|
|
|
@ -1,13 +1,10 @@
|
||||||
#include "NISSAN-LEAF-BATTERY.h"
|
#include "NISSAN-LEAF-BATTERY.h"
|
||||||
#include "../include.h"
|
|
||||||
#ifdef MQTT
|
|
||||||
#include "../devboard/mqtt/mqtt.h"
|
|
||||||
#endif
|
|
||||||
#include "../communication/can/comm_can.h"
|
#include "../communication/can/comm_can.h"
|
||||||
#include "../datalayer/datalayer.h"
|
#include "../datalayer/datalayer.h"
|
||||||
#include "../datalayer/datalayer_extended.h" //For "More battery info" webpage
|
#include "../datalayer/datalayer_extended.h" //For "More battery info" webpage
|
||||||
#include "../devboard/utils/events.h"
|
#include "../devboard/utils/events.h"
|
||||||
#include "../devboard/utils/logging.h"
|
#include "../devboard/utils/logging.h"
|
||||||
|
#include "../include.h"
|
||||||
|
|
||||||
#include "../charger/CanCharger.h"
|
#include "../charger/CanCharger.h"
|
||||||
|
|
||||||
|
|
|
@ -11,7 +11,7 @@
|
||||||
|
|
||||||
class RjxzsBms : public CanBattery {
|
class RjxzsBms : public CanBattery {
|
||||||
public:
|
public:
|
||||||
RjxzsBms() : CanBattery(true) {}
|
RjxzsBms() : CanBattery(CAN_Speed::CAN_SPEED_250KBPS) {}
|
||||||
|
|
||||||
virtual void setup(void);
|
virtual void setup(void);
|
||||||
virtual void handle_incoming_can_frame(CAN_frame rx_frame);
|
virtual void handle_incoming_can_frame(CAN_frame rx_frame);
|
||||||
|
|
|
@ -3,8 +3,11 @@
|
||||||
|
|
||||||
#include "src/communication/Transmitter.h"
|
#include "src/communication/Transmitter.h"
|
||||||
#include "src/communication/can/CanReceiver.h"
|
#include "src/communication/can/CanReceiver.h"
|
||||||
|
#include "src/communication/can/comm_can.h"
|
||||||
#include "src/devboard/utils/types.h"
|
#include "src/devboard/utils/types.h"
|
||||||
|
|
||||||
|
enum class ShuntType { None = 0, BmwSbox = 1, Highest };
|
||||||
|
|
||||||
class CanShunt : public Transmitter, CanReceiver {
|
class CanShunt : public Transmitter, CanReceiver {
|
||||||
public:
|
public:
|
||||||
virtual void setup() = 0;
|
virtual void setup() = 0;
|
||||||
|
@ -34,4 +37,8 @@ class CanShunt : public Transmitter, CanReceiver {
|
||||||
|
|
||||||
extern CanShunt* shunt;
|
extern CanShunt* shunt;
|
||||||
|
|
||||||
|
extern std::vector<ShuntType> supported_shunt_types();
|
||||||
|
extern const char* name_for_shunt_type(ShuntType type);
|
||||||
|
extern ShuntType user_selected_shunt_type;
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -2,7 +2,35 @@
|
||||||
#include "Shunt.h"
|
#include "Shunt.h"
|
||||||
|
|
||||||
CanShunt* shunt = nullptr;
|
CanShunt* shunt = nullptr;
|
||||||
|
ShuntType user_selected_shunt_type = ShuntType::None;
|
||||||
|
|
||||||
|
#ifdef COMMON_IMAGE
|
||||||
|
#ifdef SELECTED_SHUNT_CLASS
|
||||||
|
#error "Compile time SELECTED_SHUNT_CLASS should not be defined with COMMON_IMAGE"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
void setup_can_shunt() {
|
||||||
|
if (shunt) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
switch (user_selected_shunt_type) {
|
||||||
|
case ShuntType::None:
|
||||||
|
shunt = nullptr;
|
||||||
|
return;
|
||||||
|
case ShuntType::BmwSbox:
|
||||||
|
shunt = new BmwSbox();
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (shunt) {
|
||||||
|
shunt->setup();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
#else
|
||||||
void setup_can_shunt() {
|
void setup_can_shunt() {
|
||||||
if (shunt) {
|
if (shunt) {
|
||||||
return;
|
return;
|
||||||
|
@ -15,3 +43,25 @@ void setup_can_shunt() {
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
extern std::vector<ShuntType> supported_shunt_types() {
|
||||||
|
std::vector<ShuntType> types;
|
||||||
|
|
||||||
|
for (int i = 0; i < (int)ShuntType::Highest; i++) {
|
||||||
|
types.push_back((ShuntType)i);
|
||||||
|
}
|
||||||
|
|
||||||
|
return types;
|
||||||
|
}
|
||||||
|
|
||||||
|
extern const char* name_for_shunt_type(ShuntType type) {
|
||||||
|
switch (type) {
|
||||||
|
case ShuntType::None:
|
||||||
|
return "None";
|
||||||
|
case ShuntType::BmwSbox:
|
||||||
|
return BmwSbox::Name;
|
||||||
|
default:
|
||||||
|
return nullptr;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
|
@ -1765,20 +1765,20 @@ void TeslaModel3YBattery::setup(void) { // Performs one time setup at startup
|
||||||
|
|
||||||
strncpy(datalayer.system.info.battery_protocol, Name, 63);
|
strncpy(datalayer.system.info.battery_protocol, Name, 63);
|
||||||
datalayer.system.info.battery_protocol[63] = '\0';
|
datalayer.system.info.battery_protocol[63] = '\0';
|
||||||
#ifdef LFP_CHEMISTRY
|
|
||||||
datalayer.battery.info.chemistry = battery_chemistry_enum::LFP;
|
if (datalayer.battery.info.chemistry == battery_chemistry_enum::LFP) {
|
||||||
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_3Y_LFP;
|
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_3Y_LFP;
|
||||||
datalayer.battery.info.min_design_voltage_dV = MIN_PACK_VOLTAGE_3Y_LFP;
|
datalayer.battery.info.min_design_voltage_dV = MIN_PACK_VOLTAGE_3Y_LFP;
|
||||||
datalayer.battery.info.max_cell_voltage_mV = MAX_CELL_VOLTAGE_LFP;
|
datalayer.battery.info.max_cell_voltage_mV = MAX_CELL_VOLTAGE_LFP;
|
||||||
datalayer.battery.info.min_cell_voltage_mV = MIN_CELL_VOLTAGE_LFP;
|
datalayer.battery.info.min_cell_voltage_mV = MIN_CELL_VOLTAGE_LFP;
|
||||||
datalayer.battery.info.max_cell_voltage_deviation_mV = MAX_CELL_DEVIATION_LFP;
|
datalayer.battery.info.max_cell_voltage_deviation_mV = MAX_CELL_DEVIATION_LFP;
|
||||||
#else // Startup in NCM/A mode
|
} else {
|
||||||
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_3Y_NCMA;
|
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_3Y_NCMA;
|
||||||
datalayer.battery.info.min_design_voltage_dV = MIN_PACK_VOLTAGE_3Y_NCMA;
|
datalayer.battery.info.min_design_voltage_dV = MIN_PACK_VOLTAGE_3Y_NCMA;
|
||||||
datalayer.battery.info.max_cell_voltage_mV = MAX_CELL_VOLTAGE_NCA_NCM;
|
datalayer.battery.info.max_cell_voltage_mV = MAX_CELL_VOLTAGE_NCA_NCM;
|
||||||
datalayer.battery.info.min_cell_voltage_mV = MIN_CELL_VOLTAGE_NCA_NCM;
|
datalayer.battery.info.min_cell_voltage_mV = MIN_CELL_VOLTAGE_NCA_NCM;
|
||||||
datalayer.battery.info.max_cell_voltage_deviation_mV = MAX_CELL_DEVIATION_NCA_NCM;
|
datalayer.battery.info.max_cell_voltage_deviation_mV = MAX_CELL_DEVIATION_NCA_NCM;
|
||||||
#endif // !LFP_CHEMISTRY
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void TeslaModelSXBattery::setup(void) {
|
void TeslaModelSXBattery::setup(void) {
|
||||||
|
|
|
@ -508,7 +508,8 @@ class TeslaBattery : public CanBattery {
|
||||||
|
|
||||||
class TeslaModel3YBattery : public TeslaBattery {
|
class TeslaModel3YBattery : public TeslaBattery {
|
||||||
public:
|
public:
|
||||||
TeslaModel3YBattery() {
|
TeslaModel3YBattery(battery_chemistry_enum chemistry) {
|
||||||
|
datalayer.battery.info.chemistry = chemistry;
|
||||||
#ifdef EXP_TESLA_BMS_DIGITAL_HVIL
|
#ifdef EXP_TESLA_BMS_DIGITAL_HVIL
|
||||||
operate_contactors = true;
|
operate_contactors = true;
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -2,7 +2,7 @@
|
||||||
#include "../datalayer/datalayer.h"
|
#include "../datalayer/datalayer.h"
|
||||||
#include "../include.h"
|
#include "../include.h"
|
||||||
|
|
||||||
static void print_units(char* header, int value, char* units) {
|
static void print_units(const char* header, int value, const char* units) {
|
||||||
logging.print(header);
|
logging.print(header);
|
||||||
logging.print(value);
|
logging.print(value);
|
||||||
logging.print(units);
|
logging.print(units);
|
||||||
|
|
|
@ -8,7 +8,4 @@ class CanReceiver {
|
||||||
virtual void receive_can_frame(CAN_frame* rx_frame) = 0;
|
virtual void receive_can_frame(CAN_frame* rx_frame) = 0;
|
||||||
};
|
};
|
||||||
|
|
||||||
// Register a receiver object for a given CAN interface
|
|
||||||
void register_can_receiver(CanReceiver* receiver, CAN_Interface interface, bool halfSpeed = false);
|
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -1,26 +1,21 @@
|
||||||
#include "comm_can.h"
|
#include "comm_can.h"
|
||||||
|
#include <algorithm>
|
||||||
#include <map>
|
#include <map>
|
||||||
#include "../../include.h"
|
#include "../../include.h"
|
||||||
|
#include "../../lib/miwagner-ESP32-Arduino-CAN/ESP32CAN.h"
|
||||||
|
#include "../../lib/pierremolinaro-ACAN2517FD/ACAN2517FD.h"
|
||||||
|
#include "../../lib/pierremolinaro-acan2515/ACAN2515.h"
|
||||||
|
#include "comm_can.h"
|
||||||
#include "src/devboard/sdcard/sdcard.h"
|
#include "src/devboard/sdcard/sdcard.h"
|
||||||
#include "src/devboard/utils/logging.h"
|
#include "src/devboard/utils/logging.h"
|
||||||
|
|
||||||
struct CanReceiverRegistration {
|
struct CanReceiverRegistration {
|
||||||
CanReceiver* receiver;
|
CanReceiver* receiver;
|
||||||
bool halfSpeed;
|
CAN_Speed speed;
|
||||||
};
|
};
|
||||||
|
|
||||||
static std::multimap<CAN_Interface, CanReceiverRegistration> can_receivers;
|
static std::multimap<CAN_Interface, CanReceiverRegistration> can_receivers;
|
||||||
|
|
||||||
bool hasHalfSpeedReceivers(const CAN_Interface& iface) {
|
|
||||||
auto range = can_receivers.equal_range(iface);
|
|
||||||
for (auto it = range.first; it != range.second; ++it) {
|
|
||||||
if (it->second.halfSpeed) {
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Parameters
|
// Parameters
|
||||||
CAN_device_t CAN_cfg; // CAN Config
|
CAN_device_t CAN_cfg; // CAN Config
|
||||||
const uint8_t rx_queue_size = 10; // Receive Queue size
|
const uint8_t rx_queue_size = 10; // Receive Queue size
|
||||||
|
@ -29,50 +24,93 @@ volatile bool send_ok_2515 = 0;
|
||||||
volatile bool send_ok_2518 = 0;
|
volatile bool send_ok_2518 = 0;
|
||||||
static unsigned long previousMillis10 = 0;
|
static unsigned long previousMillis10 = 0;
|
||||||
|
|
||||||
|
#ifdef USE_CANFD_INTERFACE_AS_CLASSIC_CAN
|
||||||
|
const bool use_canfd_as_can_default = true;
|
||||||
|
#else
|
||||||
|
const bool use_canfd_as_can_default = false;
|
||||||
|
#endif
|
||||||
|
bool use_canfd_as_can = use_canfd_as_can_default;
|
||||||
|
|
||||||
void map_can_frame_to_variable(CAN_frame* rx_frame, CAN_Interface interface);
|
void map_can_frame_to_variable(CAN_frame* rx_frame, CAN_Interface interface);
|
||||||
|
|
||||||
#ifdef CAN_ADDON
|
void register_can_receiver(CanReceiver* receiver, CAN_Interface interface, CAN_Speed speed) {
|
||||||
|
can_receivers.insert({interface, {receiver, speed}});
|
||||||
|
DEBUG_PRINTF("CAN receiver registered, total: %d\n", can_receivers.size());
|
||||||
|
}
|
||||||
|
|
||||||
static const uint32_t QUARTZ_FREQUENCY = CRYSTAL_FREQUENCY_MHZ * 1000000UL; //MHZ configured in USER_SETTINGS.h
|
static const uint32_t QUARTZ_FREQUENCY = CRYSTAL_FREQUENCY_MHZ * 1000000UL; //MHZ configured in USER_SETTINGS.h
|
||||||
SPIClass SPI2515;
|
SPIClass SPI2515;
|
||||||
ACAN2515 can(MCP2515_CS, SPI2515, MCP2515_INT);
|
|
||||||
|
ACAN2515* can2515;
|
||||||
|
ACAN2515Settings* settings2515;
|
||||||
|
|
||||||
static ACAN2515_Buffer16 gBuffer;
|
static ACAN2515_Buffer16 gBuffer;
|
||||||
#endif //CAN_ADDON
|
|
||||||
#ifdef CANFD_ADDON
|
|
||||||
SPIClass SPI2517;
|
SPIClass SPI2517;
|
||||||
ACAN2517FD canfd(MCP2517_CS, SPI2517, MCP2517_INT);
|
ACAN2517FD* canfd;
|
||||||
#endif //CANFD_ADDON
|
ACAN2517FDSettings* settings2517;
|
||||||
|
|
||||||
// Initialization functions
|
// Initialization functions
|
||||||
|
|
||||||
void init_CAN() {
|
bool native_can_initialized = false;
|
||||||
DEBUG_PRINTF("init_CAN called\n");
|
|
||||||
// CAN pins
|
|
||||||
#ifdef CAN_SE_PIN
|
|
||||||
pinMode(CAN_SE_PIN, OUTPUT);
|
|
||||||
digitalWrite(CAN_SE_PIN, LOW);
|
|
||||||
#endif // CAN_SE_PIN
|
|
||||||
|
|
||||||
// Half-speed currently only supported for CAN_NATIVE
|
bool init_CAN() {
|
||||||
auto anyHalfSpeedNative = hasHalfSpeedReceivers(CAN_Interface::CAN_NATIVE);
|
|
||||||
|
|
||||||
CAN_cfg.speed = anyHalfSpeedNative ? CAN_SPEED_250KBPS : CAN_SPEED_500KBPS;
|
auto nativeIt = can_receivers.find(CAN_NATIVE);
|
||||||
CAN_cfg.tx_pin_id = CAN_TX_PIN;
|
if (nativeIt != can_receivers.end()) {
|
||||||
CAN_cfg.rx_pin_id = CAN_RX_PIN;
|
auto se_pin = esp32hal->CAN_SE_PIN();
|
||||||
|
auto tx_pin = esp32hal->CAN_TX_PIN();
|
||||||
|
auto rx_pin = esp32hal->CAN_RX_PIN();
|
||||||
|
|
||||||
|
if (se_pin != GPIO_NUM_NC) {
|
||||||
|
if (!esp32hal->alloc_pins("CAN", se_pin)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
pinMode(se_pin, OUTPUT);
|
||||||
|
digitalWrite(se_pin, LOW);
|
||||||
|
}
|
||||||
|
|
||||||
|
CAN_cfg.speed = (CAN_speed_t)nativeIt->second.speed;
|
||||||
|
|
||||||
|
if (!esp32hal->alloc_pins("CAN", tx_pin, rx_pin)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
CAN_cfg.tx_pin_id = tx_pin;
|
||||||
|
CAN_cfg.rx_pin_id = rx_pin;
|
||||||
CAN_cfg.rx_queue = xQueueCreate(rx_queue_size, sizeof(CAN_frame_t));
|
CAN_cfg.rx_queue = xQueueCreate(rx_queue_size, sizeof(CAN_frame_t));
|
||||||
// Init CAN Module
|
// Init CAN Module
|
||||||
ESP32Can.CANInit();
|
ESP32Can.CANInit();
|
||||||
|
native_can_initialized = true;
|
||||||
|
}
|
||||||
|
|
||||||
DEBUG_PRINTF("init_CAN performed\n");
|
auto addonIt = can_receivers.find(CAN_ADDON_MCP2515);
|
||||||
|
if (addonIt != can_receivers.end()) {
|
||||||
|
auto cs_pin = esp32hal->MCP2515_CS();
|
||||||
|
auto int_pin = esp32hal->MCP2515_INT();
|
||||||
|
auto sck_pin = esp32hal->MCP2515_SCK();
|
||||||
|
auto miso_pin = esp32hal->MCP2515_MISO();
|
||||||
|
auto mosi_pin = esp32hal->MCP2515_MOSI();
|
||||||
|
|
||||||
|
if (!esp32hal->alloc_pins("CAN", cs_pin, int_pin, sck_pin, miso_pin, mosi_pin)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
#ifdef CAN_ADDON
|
|
||||||
#ifdef DEBUG_LOG
|
#ifdef DEBUG_LOG
|
||||||
logging.println("Dual CAN Bus (ESP32+MCP2515) selected");
|
logging.println("Dual CAN Bus (ESP32+MCP2515) selected");
|
||||||
#endif // DEBUG_LOG
|
#endif // DEBUG_LOG
|
||||||
gBuffer.initWithSize(25);
|
gBuffer.initWithSize(25);
|
||||||
SPI2515.begin(MCP2515_SCK, MCP2515_MISO, MCP2515_MOSI);
|
|
||||||
ACAN2515Settings settings2515(QUARTZ_FREQUENCY, 500UL * 1000UL); // CAN bit rate 500 kb/s
|
can2515 = new ACAN2515(cs_pin, SPI2515, int_pin);
|
||||||
settings2515.mRequestedMode = ACAN2515Settings::NormalMode;
|
|
||||||
const uint16_t errorCode2515 = can.begin(settings2515, [] { can.isr(); });
|
SPI2515.begin(sck_pin, miso_pin, mosi_pin);
|
||||||
|
|
||||||
|
// CAN bit rate 250 or 500 kb/s
|
||||||
|
auto bitRate = (int)addonIt->second.speed * 1000UL;
|
||||||
|
|
||||||
|
settings2515 = new ACAN2515Settings(QUARTZ_FREQUENCY, bitRate);
|
||||||
|
settings2515->mRequestedMode = ACAN2515Settings::NormalMode;
|
||||||
|
const uint16_t errorCode2515 = can2515->begin(*settings2515, [] { can2515->isr(); });
|
||||||
if (errorCode2515 == 0) {
|
if (errorCode2515 == 0) {
|
||||||
#ifdef DEBUG_LOG
|
#ifdef DEBUG_LOG
|
||||||
logging.println("Can ok");
|
logging.println("Can ok");
|
||||||
|
@ -83,40 +121,60 @@ void init_CAN() {
|
||||||
logging.println(errorCode2515, HEX);
|
logging.println(errorCode2515, HEX);
|
||||||
#endif // DEBUG_LOG
|
#endif // DEBUG_LOG
|
||||||
set_event(EVENT_CANMCP2515_INIT_FAILURE, (uint8_t)errorCode2515);
|
set_event(EVENT_CANMCP2515_INIT_FAILURE, (uint8_t)errorCode2515);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
#endif // CAN_ADDON
|
|
||||||
|
|
||||||
#ifdef CANFD_ADDON
|
auto fdNativeIt = can_receivers.find(CANFD_NATIVE);
|
||||||
|
auto fdAddonIt = can_receivers.find(CANFD_ADDON_MCP2518);
|
||||||
|
|
||||||
|
if (fdNativeIt != can_receivers.end() || fdAddonIt != can_receivers.end()) {
|
||||||
|
|
||||||
|
auto speed = (fdNativeIt != can_receivers.end()) ? fdNativeIt->second.speed : fdAddonIt->second.speed;
|
||||||
|
|
||||||
|
auto cs_pin = esp32hal->MCP2517_CS();
|
||||||
|
auto int_pin = esp32hal->MCP2517_INT();
|
||||||
|
auto sck_pin = esp32hal->MCP2517_SCK();
|
||||||
|
auto sdo_pin = esp32hal->MCP2517_SDO();
|
||||||
|
auto sdi_pin = esp32hal->MCP2517_SDI();
|
||||||
|
|
||||||
|
if (!esp32hal->alloc_pins("CAN", cs_pin, int_pin, sck_pin, sdo_pin, sdi_pin)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
canfd = new ACAN2517FD(cs_pin, SPI2517, int_pin);
|
||||||
|
|
||||||
#ifdef DEBUG_LOG
|
#ifdef DEBUG_LOG
|
||||||
logging.println("CAN FD add-on (ESP32+MCP2517) selected");
|
logging.println("CAN FD add-on (ESP32+MCP2517) selected");
|
||||||
#endif // DEBUG_LOG
|
#endif // DEBUG_LOG
|
||||||
SPI2517.begin(MCP2517_SCK, MCP2517_SDO, MCP2517_SDI);
|
SPI2517.begin(sck_pin, sdo_pin, sdi_pin);
|
||||||
ACAN2517FDSettings settings2517(CANFD_ADDON_CRYSTAL_FREQUENCY_MHZ, 500 * 1000,
|
auto bitRate = (int)speed * 1000UL;
|
||||||
DataBitRateFactor::x4); // Arbitration bit rate: 500 kbit/s, data bit rate: 2 Mbit/s
|
settings2517 = new ACAN2517FDSettings(
|
||||||
#ifdef USE_CANFD_INTERFACE_AS_CLASSIC_CAN
|
CANFD_ADDON_CRYSTAL_FREQUENCY_MHZ, bitRate,
|
||||||
settings2517.mRequestedMode = ACAN2517FDSettings::Normal20B; // ListenOnly / Normal20B / NormalFD
|
DataBitRateFactor::x4); // Arbitration bit rate: 250/500 kbit/s, data bit rate: 1/2 Mbit/s
|
||||||
#else // not USE_CANFD_INTERFACE_AS_CLASSIC_CAN
|
|
||||||
settings2517.mRequestedMode = ACAN2517FDSettings::NormalFD; // ListenOnly / Normal20B / NormalFD
|
// ListenOnly / Normal20B / NormalFD
|
||||||
#endif // USE_CANFD_INTERFACE_AS_CLASSIC_CAN
|
settings2517->mRequestedMode = use_canfd_as_can ? ACAN2517FDSettings::Normal20B : ACAN2517FDSettings::NormalFD;
|
||||||
const uint32_t errorCode2517 = canfd.begin(settings2517, [] { canfd.isr(); });
|
|
||||||
canfd.poll();
|
const uint32_t errorCode2517 = canfd->begin(*settings2517, [] { canfd->isr(); });
|
||||||
|
canfd->poll();
|
||||||
if (errorCode2517 == 0) {
|
if (errorCode2517 == 0) {
|
||||||
#ifdef DEBUG_LOG
|
#ifdef DEBUG_LOG
|
||||||
logging.print("Bit Rate prescaler: ");
|
logging.print("Bit Rate prescaler: ");
|
||||||
logging.println(settings2517.mBitRatePrescaler);
|
logging.println(settings2517->mBitRatePrescaler);
|
||||||
logging.print("Arbitration Phase segment 1: ");
|
logging.print("Arbitration Phase segment 1: ");
|
||||||
logging.print(settings2517.mArbitrationPhaseSegment1);
|
logging.print(settings2517->mArbitrationPhaseSegment1);
|
||||||
logging.print(" segment 2: ");
|
logging.print(" segment 2: ");
|
||||||
logging.print(settings2517.mArbitrationPhaseSegment2);
|
logging.print(settings2517->mArbitrationPhaseSegment2);
|
||||||
logging.print(" SJW: ");
|
logging.print(" SJW: ");
|
||||||
logging.println(settings2517.mArbitrationSJW);
|
logging.println(settings2517->mArbitrationSJW);
|
||||||
logging.print("Actual Arbitration Bit Rate: ");
|
logging.print("Actual Arbitration Bit Rate: ");
|
||||||
logging.print(settings2517.actualArbitrationBitRate());
|
logging.print(settings2517->actualArbitrationBitRate());
|
||||||
logging.print(" bit/s");
|
logging.print(" bit/s");
|
||||||
logging.print(" (Exact:");
|
logging.print(" (Exact:");
|
||||||
logging.println(settings2517.exactArbitrationBitRate() ? "yes)" : "no)");
|
logging.println(settings2517->exactArbitrationBitRate() ? "yes)" : "no)");
|
||||||
logging.print("Arbitration Sample point: ");
|
logging.print("Arbitration Sample point: ");
|
||||||
logging.print(settings2517.arbitrationSamplePointFromBitStart());
|
logging.print(settings2517->arbitrationSamplePointFromBitStart());
|
||||||
logging.println("%");
|
logging.println("%");
|
||||||
#endif // DEBUG_LOG
|
#endif // DEBUG_LOG
|
||||||
} else {
|
} else {
|
||||||
|
@ -125,8 +183,11 @@ void init_CAN() {
|
||||||
logging.println(errorCode2517, HEX);
|
logging.println(errorCode2517, HEX);
|
||||||
#endif // DEBUG_LOG
|
#endif // DEBUG_LOG
|
||||||
set_event(EVENT_CANMCP2517FD_INIT_FAILURE, (uint8_t)errorCode2517);
|
set_event(EVENT_CANMCP2517FD_INIT_FAILURE, (uint8_t)errorCode2517);
|
||||||
|
return false;
|
||||||
}
|
}
|
||||||
#endif // CANFD_ADDON
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
void transmit_can_frame(CAN_frame* tx_frame, int interface) {
|
void transmit_can_frame(CAN_frame* tx_frame, int interface) {
|
||||||
|
@ -156,7 +217,6 @@ void transmit_can_frame(CAN_frame* tx_frame, int interface) {
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case CAN_ADDON_MCP2515: {
|
case CAN_ADDON_MCP2515: {
|
||||||
#ifdef CAN_ADDON
|
|
||||||
//Struct with ACAN2515 library format, needed to use the MCP2515 library for CAN2
|
//Struct with ACAN2515 library format, needed to use the MCP2515 library for CAN2
|
||||||
CANMessage MCP2515Frame;
|
CANMessage MCP2515Frame;
|
||||||
MCP2515Frame.id = tx_frame->ID;
|
MCP2515Frame.id = tx_frame->ID;
|
||||||
|
@ -167,17 +227,13 @@ void transmit_can_frame(CAN_frame* tx_frame, int interface) {
|
||||||
MCP2515Frame.data[i] = tx_frame->data.u8[i];
|
MCP2515Frame.data[i] = tx_frame->data.u8[i];
|
||||||
}
|
}
|
||||||
|
|
||||||
send_ok_2515 = can.tryToSend(MCP2515Frame);
|
send_ok_2515 = can2515->tryToSend(MCP2515Frame);
|
||||||
if (!send_ok_2515) {
|
if (!send_ok_2515) {
|
||||||
datalayer.system.info.can_2515_send_fail = true;
|
datalayer.system.info.can_2515_send_fail = true;
|
||||||
}
|
}
|
||||||
#else // Interface not compiled, and settings try to use it
|
|
||||||
set_event(EVENT_INTERFACE_MISSING, interface);
|
|
||||||
#endif //CAN_ADDON
|
|
||||||
} break;
|
} break;
|
||||||
case CANFD_NATIVE:
|
case CANFD_NATIVE:
|
||||||
case CANFD_ADDON_MCP2518: {
|
case CANFD_ADDON_MCP2518: {
|
||||||
#ifdef CANFD_ADDON
|
|
||||||
CANFDMessage MCP2518Frame;
|
CANFDMessage MCP2518Frame;
|
||||||
if (tx_frame->FD) {
|
if (tx_frame->FD) {
|
||||||
MCP2518Frame.type = CANFDMessage::CANFD_WITH_BIT_RATE_SWITCH;
|
MCP2518Frame.type = CANFDMessage::CANFD_WITH_BIT_RATE_SWITCH;
|
||||||
|
@ -190,13 +246,10 @@ void transmit_can_frame(CAN_frame* tx_frame, int interface) {
|
||||||
for (uint8_t i = 0; i < MCP2518Frame.len; i++) {
|
for (uint8_t i = 0; i < MCP2518Frame.len; i++) {
|
||||||
MCP2518Frame.data[i] = tx_frame->data.u8[i];
|
MCP2518Frame.data[i] = tx_frame->data.u8[i];
|
||||||
}
|
}
|
||||||
send_ok_2518 = canfd.tryToSend(MCP2518Frame);
|
send_ok_2518 = canfd->tryToSend(MCP2518Frame);
|
||||||
if (!send_ok_2518) {
|
if (!send_ok_2518) {
|
||||||
datalayer.system.info.can_2518_send_fail = true;
|
datalayer.system.info.can_2518_send_fail = true;
|
||||||
}
|
}
|
||||||
#else // Interface not compiled, and settings try to use it
|
|
||||||
set_event(EVENT_INTERFACE_MISSING, interface);
|
|
||||||
#endif //CANFD_ADDON
|
|
||||||
} break;
|
} break;
|
||||||
default:
|
default:
|
||||||
// Invalid interface sent with function call. TODO: Raise event that coders messed up
|
// Invalid interface sent with function call. TODO: Raise event that coders messed up
|
||||||
|
@ -206,13 +259,17 @@ void transmit_can_frame(CAN_frame* tx_frame, int interface) {
|
||||||
|
|
||||||
// Receive functions
|
// Receive functions
|
||||||
void receive_can() {
|
void receive_can() {
|
||||||
|
if (native_can_initialized) {
|
||||||
receive_frame_can_native(); // Receive CAN messages from native CAN port
|
receive_frame_can_native(); // Receive CAN messages from native CAN port
|
||||||
#ifdef CAN_ADDON
|
}
|
||||||
|
|
||||||
|
if (can2515) {
|
||||||
receive_frame_can_addon(); // Receive CAN messages on add-on MCP2515 chip
|
receive_frame_can_addon(); // Receive CAN messages on add-on MCP2515 chip
|
||||||
#endif // CAN_ADDON
|
}
|
||||||
#ifdef CANFD_ADDON
|
|
||||||
|
if (canfd) {
|
||||||
receive_frame_canfd_addon(); // Receive CAN-FD messages.
|
receive_frame_canfd_addon(); // Receive CAN-FD messages.
|
||||||
#endif // CANFD_ADDON
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void receive_frame_can_native() { // This section checks if we have a complete CAN message incoming on native CAN port
|
void receive_frame_can_native() { // This section checks if we have a complete CAN message incoming on native CAN port
|
||||||
|
@ -234,13 +291,12 @@ void receive_frame_can_native() { // This section checks if we have a complete
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef CAN_ADDON
|
|
||||||
void receive_frame_can_addon() { // This section checks if we have a complete CAN message incoming on add-on CAN port
|
void receive_frame_can_addon() { // This section checks if we have a complete CAN message incoming on add-on CAN port
|
||||||
CAN_frame rx_frame; // Struct with our CAN format
|
CAN_frame rx_frame; // Struct with our CAN format
|
||||||
CANMessage MCP2515frame; // Struct with ACAN2515 library format, needed to use the MCP2515 library
|
CANMessage MCP2515frame; // Struct with ACAN2515 library format, needed to use the MCP2515 library
|
||||||
|
|
||||||
if (can.available()) {
|
if (can2515->available()) {
|
||||||
can.receive(MCP2515frame);
|
can2515->receive(MCP2515frame);
|
||||||
|
|
||||||
rx_frame.ID = MCP2515frame.id;
|
rx_frame.ID = MCP2515frame.id;
|
||||||
rx_frame.ext_ID = MCP2515frame.ext ? CAN_frame_ext : CAN_frame_std;
|
rx_frame.ext_ID = MCP2515frame.ext ? CAN_frame_ext : CAN_frame_std;
|
||||||
|
@ -253,26 +309,23 @@ void receive_frame_can_addon() { // This section checks if we have a complete C
|
||||||
map_can_frame_to_variable(&rx_frame, CAN_ADDON_MCP2515);
|
map_can_frame_to_variable(&rx_frame, CAN_ADDON_MCP2515);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif // CAN_ADDON
|
|
||||||
|
|
||||||
#ifdef CANFD_ADDON
|
|
||||||
void receive_frame_canfd_addon() { // This section checks if we have a complete CAN-FD message incoming
|
void receive_frame_canfd_addon() { // This section checks if we have a complete CAN-FD message incoming
|
||||||
CANFDMessage MCP2518frame;
|
CANFDMessage MCP2518frame;
|
||||||
int count = 0;
|
int count = 0;
|
||||||
while (canfd.available() && count++ < 16) {
|
while (canfd->available() && count++ < 16) {
|
||||||
canfd.receive(MCP2518frame);
|
canfd->receive(MCP2518frame);
|
||||||
|
|
||||||
CAN_frame rx_frame;
|
CAN_frame rx_frame;
|
||||||
rx_frame.ID = MCP2518frame.id;
|
rx_frame.ID = MCP2518frame.id;
|
||||||
rx_frame.ext_ID = MCP2518frame.ext;
|
rx_frame.ext_ID = MCP2518frame.ext;
|
||||||
rx_frame.DLC = MCP2518frame.len;
|
rx_frame.DLC = MCP2518frame.len;
|
||||||
memcpy(rx_frame.data.u8, MCP2518frame.data, MIN(rx_frame.DLC, 64));
|
memcpy(rx_frame.data.u8, MCP2518frame.data, std::min(rx_frame.DLC, (uint8_t)64));
|
||||||
//message incoming, pass it on to the handler
|
//message incoming, pass it on to the handler
|
||||||
map_can_frame_to_variable(&rx_frame, CANFD_ADDON_MCP2518);
|
map_can_frame_to_variable(&rx_frame, CANFD_ADDON_MCP2518);
|
||||||
map_can_frame_to_variable(&rx_frame, CANFD_NATIVE);
|
map_can_frame_to_variable(&rx_frame, CANFD_NATIVE);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif // CANFD_ADDON
|
|
||||||
|
|
||||||
// Support functions
|
// Support functions
|
||||||
void print_can_frame(CAN_frame frame, frameDirection msgDir) {
|
void print_can_frame(CAN_frame frame, frameDirection msgDir) {
|
||||||
|
@ -299,11 +352,6 @@ void print_can_frame(CAN_frame frame, frameDirection msgDir) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void register_can_receiver(CanReceiver* receiver, CAN_Interface interface, bool halfSpeed) {
|
|
||||||
can_receivers.insert({interface, {receiver, halfSpeed}});
|
|
||||||
DEBUG_PRINTF("CAN receiver registered, total: %d\n", can_receivers.size());
|
|
||||||
}
|
|
||||||
|
|
||||||
void map_can_frame_to_variable(CAN_frame* rx_frame, CAN_Interface interface) {
|
void map_can_frame_to_variable(CAN_frame* rx_frame, CAN_Interface interface) {
|
||||||
if (interface !=
|
if (interface !=
|
||||||
CANFD_NATIVE) { //Avoid printing twice due to receive_frame_canfd_addon sending to both FD interfaces
|
CANFD_NATIVE) { //Avoid printing twice due to receive_frame_canfd_addon sending to both FD interfaces
|
||||||
|
@ -361,3 +409,45 @@ void dump_can_frame(CAN_frame& frame, frameDirection msgDir) {
|
||||||
|
|
||||||
datalayer.system.info.logged_can_messages_offset = offset; // Update offset in buffer
|
datalayer.system.info.logged_can_messages_offset = offset; // Update offset in buffer
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void stop_can() {
|
||||||
|
if (can_receivers.find(CAN_NATIVE) != can_receivers.end()) {
|
||||||
|
ESP32Can.CANStop();
|
||||||
|
}
|
||||||
|
|
||||||
|
if (can2515) {
|
||||||
|
can2515->end();
|
||||||
|
SPI2515.end();
|
||||||
|
}
|
||||||
|
|
||||||
|
if (canfd) {
|
||||||
|
canfd->end();
|
||||||
|
SPI2517.end();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void restart_can() {
|
||||||
|
if (can_receivers.find(CAN_NATIVE) != can_receivers.end()) {
|
||||||
|
ESP32Can.CANInit();
|
||||||
|
}
|
||||||
|
|
||||||
|
if (can2515) {
|
||||||
|
SPI2515.begin();
|
||||||
|
can2515->begin(*settings2515, [] { can2515->isr(); });
|
||||||
|
}
|
||||||
|
|
||||||
|
if (canfd) {
|
||||||
|
SPI2517.begin();
|
||||||
|
canfd->begin(*settings2517, [] { can2515->isr(); });
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
CAN_Speed change_can_speed(CAN_Interface interface, CAN_Speed speed) {
|
||||||
|
auto oldSpeed = (CAN_Speed)CAN_cfg.speed;
|
||||||
|
if (interface == CAN_Interface::CAN_NATIVE) {
|
||||||
|
CAN_cfg.speed = (CAN_speed_t)speed;
|
||||||
|
// ReInit native CAN module at new speed
|
||||||
|
ESP32Can.CANInit();
|
||||||
|
}
|
||||||
|
return oldSpeed;
|
||||||
|
}
|
||||||
|
|
|
@ -1,34 +1,42 @@
|
||||||
#ifndef _COMM_CAN_H_
|
#ifndef _COMM_CAN_H_
|
||||||
#define _COMM_CAN_H_
|
#define _COMM_CAN_H_
|
||||||
|
|
||||||
#include "../../include.h"
|
#include "../../devboard/utils/types.h"
|
||||||
|
|
||||||
#include "../../datalayer/datalayer.h"
|
extern bool use_canfd_as_can;
|
||||||
#include "../../devboard/utils/events.h"
|
|
||||||
#include "../../devboard/utils/value_mapping.h"
|
|
||||||
#include "../../lib/ESP32Async-ESPAsyncWebServer/src/ESPAsyncWebServer.h"
|
|
||||||
#include "../../lib/miwagner-ESP32-Arduino-CAN/ESP32CAN.h"
|
|
||||||
#ifdef CAN_ADDON
|
|
||||||
#include "../../lib/pierremolinaro-acan2515/ACAN2515.h"
|
|
||||||
#endif //CAN_ADDON
|
|
||||||
#ifdef CANFD_ADDON
|
|
||||||
#include "../../lib/pierremolinaro-ACAN2517FD/ACAN2517FD.h"
|
|
||||||
#endif //CANFD_ADDON
|
|
||||||
|
|
||||||
void dump_can_frame(CAN_frame& frame, frameDirection msgDir);
|
void dump_can_frame(CAN_frame& frame, frameDirection msgDir);
|
||||||
void transmit_can_frame(CAN_frame* tx_frame, int interface);
|
void transmit_can_frame(CAN_frame* tx_frame, int interface);
|
||||||
|
|
||||||
|
class CanReceiver;
|
||||||
|
|
||||||
|
enum class CAN_Speed {
|
||||||
|
CAN_SPEED_100KBPS = 100,
|
||||||
|
CAN_SPEED_125KBPS = 125,
|
||||||
|
CAN_SPEED_200KBPS = 200,
|
||||||
|
CAN_SPEED_250KBPS = 250,
|
||||||
|
CAN_SPEED_500KBPS = 500,
|
||||||
|
CAN_SPEED_800KBPS = 800,
|
||||||
|
CAN_SPEED_1000KBPS = 1000
|
||||||
|
};
|
||||||
|
|
||||||
|
// Register a receiver object for a given CAN interface.
|
||||||
|
// By default receivers expect the CAN interface to be operated at "fast" speed.
|
||||||
|
// If halfSpeed is true, half speed is used.
|
||||||
|
void register_can_receiver(CanReceiver* receiver, CAN_Interface interface,
|
||||||
|
CAN_Speed speed = CAN_Speed::CAN_SPEED_500KBPS);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Initialization function for CAN.
|
* @brief Initializes all CAN interfaces requested earlier by other modules (see register_can_receiver)
|
||||||
*
|
*
|
||||||
* @param[in] void
|
* @param[in] void
|
||||||
*
|
*
|
||||||
* @return void
|
* @return true if CAN interfaces were initialized successfully, false otherwise.
|
||||||
*/
|
*/
|
||||||
void init_CAN();
|
bool init_CAN();
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Receive CAN messages from all interfaces
|
* @brief Receive CAN messages from all interfaces. Respective CanReceivers are called.
|
||||||
*
|
*
|
||||||
* @param[in] void
|
* @param[in] void
|
||||||
*
|
*
|
||||||
|
@ -72,4 +80,13 @@ void receive_frame_canfd_addon();
|
||||||
*/
|
*/
|
||||||
void print_can_frame(CAN_frame frame, frameDirection msgDir);
|
void print_can_frame(CAN_frame frame, frameDirection msgDir);
|
||||||
|
|
||||||
|
// Stop/pause CAN communication for all interfaces
|
||||||
|
void stop_can();
|
||||||
|
|
||||||
|
// Restart CAN communication for all interfaces
|
||||||
|
void restart_can();
|
||||||
|
|
||||||
|
// Change the speed of the CAN interface and return the old speed.
|
||||||
|
CAN_Speed change_can_speed(CAN_Interface interface, CAN_Speed speed);
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -25,7 +25,7 @@ bool periodic_bms_reset = periodic_bms_reset_default;
|
||||||
#ifdef REMOTE_BMS_RESET
|
#ifdef REMOTE_BMS_RESET
|
||||||
const bool remote_bms_reset_default = true;
|
const bool remote_bms_reset_default = true;
|
||||||
#else
|
#else
|
||||||
const bool remote_bms_reset_default = true;
|
const bool remote_bms_reset_default = false;
|
||||||
#endif
|
#endif
|
||||||
bool remote_bms_reset = remote_bms_reset_default;
|
bool remote_bms_reset = remote_bms_reset_default;
|
||||||
|
|
||||||
|
@ -92,41 +92,57 @@ void set(uint8_t pin, bool direction, uint32_t pwm_freq = 0xFFFF) {
|
||||||
|
|
||||||
// Initialization functions
|
// Initialization functions
|
||||||
|
|
||||||
void init_contactors() {
|
const char* contactors = "Contactors";
|
||||||
|
|
||||||
|
bool init_contactors() {
|
||||||
// Init contactor pins
|
// Init contactor pins
|
||||||
if (contactor_control_enabled) {
|
if (contactor_control_enabled) {
|
||||||
|
auto posPin = esp32hal->POSITIVE_CONTACTOR_PIN();
|
||||||
|
auto negPin = esp32hal->NEGATIVE_CONTACTOR_PIN();
|
||||||
|
auto precPin = esp32hal->PRECHARGE_PIN();
|
||||||
|
|
||||||
|
if (!esp32hal->alloc_pins(contactors, posPin, negPin, precPin)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
if (pwm_contactor_control) {
|
if (pwm_contactor_control) {
|
||||||
// Setup PWM Channel Frequency and Resolution
|
// Setup PWM Channel Frequency and Resolution
|
||||||
ledcAttachChannel(POSITIVE_CONTACTOR_PIN, PWM_Freq, PWM_Res, PWM_Positive_Channel);
|
ledcAttachChannel(posPin, PWM_Freq, PWM_Res, PWM_Positive_Channel);
|
||||||
ledcAttachChannel(NEGATIVE_CONTACTOR_PIN, PWM_Freq, PWM_Res, PWM_Negative_Channel);
|
ledcAttachChannel(negPin, PWM_Freq, PWM_Res, PWM_Negative_Channel);
|
||||||
// Set all pins OFF (0% PWM)
|
// Set all pins OFF (0% PWM)
|
||||||
ledcWrite(POSITIVE_CONTACTOR_PIN, PWM_OFF_DUTY);
|
ledcWrite(posPin, PWM_OFF_DUTY);
|
||||||
ledcWrite(NEGATIVE_CONTACTOR_PIN, PWM_OFF_DUTY);
|
ledcWrite(negPin, PWM_OFF_DUTY);
|
||||||
} else { //Normal CONTACTOR_CONTROL
|
} else { //Normal CONTACTOR_CONTROL
|
||||||
pinMode(POSITIVE_CONTACTOR_PIN, OUTPUT);
|
pinMode(posPin, OUTPUT);
|
||||||
set(POSITIVE_CONTACTOR_PIN, OFF);
|
set(posPin, OFF);
|
||||||
pinMode(NEGATIVE_CONTACTOR_PIN, OUTPUT);
|
pinMode(negPin, OUTPUT);
|
||||||
set(NEGATIVE_CONTACTOR_PIN, OFF);
|
set(negPin, OFF);
|
||||||
} // Precharge never has PWM regardless of setting
|
} // Precharge never has PWM regardless of setting
|
||||||
pinMode(PRECHARGE_PIN, OUTPUT);
|
pinMode(precPin, OUTPUT);
|
||||||
set(PRECHARGE_PIN, OFF);
|
set(precPin, OFF);
|
||||||
}
|
}
|
||||||
if (contactor_control_enabled_double_battery) {
|
|
||||||
pinMode(SECOND_BATTERY_CONTACTORS_PIN, OUTPUT);
|
|
||||||
set(SECOND_BATTERY_CONTACTORS_PIN, OFF);
|
|
||||||
}
|
|
||||||
// Init BMS contactor
|
|
||||||
#if defined HW_STARK || defined HW_3LB // This hardware has dedicated pin, always enable on start
|
|
||||||
pinMode(BMS_POWER, OUTPUT); //LilyGo is omitted from this, only enabled if user selects PERIODIC_BMS_RESET
|
|
||||||
digitalWrite(BMS_POWER, HIGH);
|
|
||||||
#endif // HW with dedicated BMS pins
|
|
||||||
|
|
||||||
#ifdef BMS_POWER
|
if (contactor_control_enabled_double_battery) {
|
||||||
if (periodic_bms_reset || remote_bms_reset) {
|
auto second_contactors = esp32hal->SECOND_BATTERY_CONTACTORS_PIN();
|
||||||
pinMode(BMS_POWER, OUTPUT);
|
if (!esp32hal->alloc_pins(contactors, second_contactors)) {
|
||||||
digitalWrite(BMS_POWER, HIGH);
|
return false;
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
pinMode(second_contactors, OUTPUT);
|
||||||
|
set(second_contactors, OFF);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Init BMS contactor
|
||||||
|
if (periodic_bms_reset || remote_bms_reset || esp32hal->always_enable_bms_power()) {
|
||||||
|
auto pin = esp32hal->BMS_POWER();
|
||||||
|
if (!esp32hal->alloc_pins("BMS power", pin)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
pinMode(pin, OUTPUT);
|
||||||
|
digitalWrite(pin, HIGH);
|
||||||
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
static void dbg_contactors(const char* state) {
|
static void dbg_contactors(const char* state) {
|
||||||
|
@ -144,9 +160,14 @@ void handle_contactors() {
|
||||||
datalayer.system.status.inverter_allows_contactor_closing = inverter->allows_contactor_closing();
|
datalayer.system.status.inverter_allows_contactor_closing = inverter->allows_contactor_closing();
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef BMS_POWER
|
auto posPin = esp32hal->POSITIVE_CONTACTOR_PIN();
|
||||||
|
auto negPin = esp32hal->NEGATIVE_CONTACTOR_PIN();
|
||||||
|
auto prechargePin = esp32hal->PRECHARGE_PIN();
|
||||||
|
auto bms_power_pin = esp32hal->BMS_POWER();
|
||||||
|
|
||||||
|
if (bms_power_pin != GPIO_NUM_NC) {
|
||||||
handle_BMSpower(); // Some batteries need to be periodically power cycled
|
handle_BMSpower(); // Some batteries need to be periodically power cycled
|
||||||
#endif
|
}
|
||||||
|
|
||||||
#ifdef CONTACTOR_CONTROL_DOUBLE_BATTERY
|
#ifdef CONTACTOR_CONTROL_DOUBLE_BATTERY
|
||||||
handle_contactors_battery2();
|
handle_contactors_battery2();
|
||||||
|
@ -166,9 +187,9 @@ void handle_contactors() {
|
||||||
}
|
}
|
||||||
|
|
||||||
if (contactorStatus == SHUTDOWN_REQUESTED) {
|
if (contactorStatus == SHUTDOWN_REQUESTED) {
|
||||||
set(PRECHARGE_PIN, OFF);
|
set(prechargePin, OFF);
|
||||||
set(NEGATIVE_CONTACTOR_PIN, OFF, PWM_OFF_DUTY);
|
set(negPin, OFF, PWM_OFF_DUTY);
|
||||||
set(POSITIVE_CONTACTOR_PIN, OFF, PWM_OFF_DUTY);
|
set(posPin, OFF, PWM_OFF_DUTY);
|
||||||
set_event(EVENT_ERROR_OPEN_CONTACTOR, 0);
|
set_event(EVENT_ERROR_OPEN_CONTACTOR, 0);
|
||||||
datalayer.system.status.contactors_engaged = false;
|
datalayer.system.status.contactors_engaged = false;
|
||||||
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)
|
||||||
|
@ -176,9 +197,9 @@ void handle_contactors() {
|
||||||
|
|
||||||
// After that, check if we are OK to start turning on the battery
|
// After that, check if we are OK to start turning on the battery
|
||||||
if (contactorStatus == DISCONNECTED) {
|
if (contactorStatus == DISCONNECTED) {
|
||||||
set(PRECHARGE_PIN, OFF);
|
set(prechargePin, OFF);
|
||||||
set(NEGATIVE_CONTACTOR_PIN, OFF, PWM_OFF_DUTY);
|
set(negPin, OFF, PWM_OFF_DUTY);
|
||||||
set(POSITIVE_CONTACTOR_PIN, OFF, PWM_OFF_DUTY);
|
set(posPin, OFF, PWM_OFF_DUTY);
|
||||||
datalayer.system.status.contactors_engaged = false;
|
datalayer.system.status.contactors_engaged = false;
|
||||||
|
|
||||||
if (datalayer.system.status.battery_allows_contactor_closing &&
|
if (datalayer.system.status.battery_allows_contactor_closing &&
|
||||||
|
@ -210,7 +231,7 @@ void handle_contactors() {
|
||||||
// Handle actual state machine. This first turns on Negative, then Precharge, then Positive, and finally turns OFF precharge
|
// Handle actual state machine. This first turns on Negative, then Precharge, then Positive, and finally turns OFF precharge
|
||||||
switch (contactorStatus) {
|
switch (contactorStatus) {
|
||||||
case START_PRECHARGE:
|
case START_PRECHARGE:
|
||||||
set(NEGATIVE_CONTACTOR_PIN, ON, PWM_ON_DUTY);
|
set(negPin, ON, PWM_ON_DUTY);
|
||||||
dbg_contactors("NEGATIVE");
|
dbg_contactors("NEGATIVE");
|
||||||
prechargeStartTime = currentTime;
|
prechargeStartTime = currentTime;
|
||||||
contactorStatus = PRECHARGE;
|
contactorStatus = PRECHARGE;
|
||||||
|
@ -218,7 +239,7 @@ void handle_contactors() {
|
||||||
|
|
||||||
case PRECHARGE:
|
case PRECHARGE:
|
||||||
if (currentTime - prechargeStartTime >= NEGATIVE_CONTACTOR_TIME_MS) {
|
if (currentTime - prechargeStartTime >= NEGATIVE_CONTACTOR_TIME_MS) {
|
||||||
set(PRECHARGE_PIN, ON);
|
set(prechargePin, ON);
|
||||||
dbg_contactors("PRECHARGE");
|
dbg_contactors("PRECHARGE");
|
||||||
negativeStartTime = currentTime;
|
negativeStartTime = currentTime;
|
||||||
contactorStatus = POSITIVE;
|
contactorStatus = POSITIVE;
|
||||||
|
@ -227,7 +248,7 @@ void handle_contactors() {
|
||||||
|
|
||||||
case POSITIVE:
|
case POSITIVE:
|
||||||
if (currentTime - negativeStartTime >= PRECHARGE_TIME_MS) {
|
if (currentTime - negativeStartTime >= PRECHARGE_TIME_MS) {
|
||||||
set(POSITIVE_CONTACTOR_PIN, ON, PWM_ON_DUTY);
|
set(posPin, ON, PWM_ON_DUTY);
|
||||||
dbg_contactors("POSITIVE");
|
dbg_contactors("POSITIVE");
|
||||||
prechargeCompletedTime = currentTime;
|
prechargeCompletedTime = currentTime;
|
||||||
contactorStatus = PRECHARGE_OFF;
|
contactorStatus = PRECHARGE_OFF;
|
||||||
|
@ -236,9 +257,9 @@ void handle_contactors() {
|
||||||
|
|
||||||
case PRECHARGE_OFF:
|
case PRECHARGE_OFF:
|
||||||
if (currentTime - prechargeCompletedTime >= PRECHARGE_COMPLETED_TIME_MS) {
|
if (currentTime - prechargeCompletedTime >= PRECHARGE_COMPLETED_TIME_MS) {
|
||||||
set(PRECHARGE_PIN, OFF);
|
set(prechargePin, OFF);
|
||||||
set(NEGATIVE_CONTACTOR_PIN, ON, PWM_HOLD_DUTY);
|
set(negPin, ON, PWM_HOLD_DUTY);
|
||||||
set(POSITIVE_CONTACTOR_PIN, ON, PWM_HOLD_DUTY);
|
set(posPin, ON, PWM_HOLD_DUTY);
|
||||||
dbg_contactors("PRECHARGE_OFF");
|
dbg_contactors("PRECHARGE_OFF");
|
||||||
contactorStatus = COMPLETED;
|
contactorStatus = COMPLETED;
|
||||||
datalayer.system.status.contactors_engaged = true;
|
datalayer.system.status.contactors_engaged = true;
|
||||||
|
@ -269,9 +290,10 @@ This makes the BMS recalculate all SOC% and avoid memory leaks
|
||||||
During that time we also set the emulator state to paused in order to not try and send CAN messages towards the battery
|
During that time we also set the emulator state to paused in order to not try and send CAN messages towards the battery
|
||||||
Feature is only used if user has enabled PERIODIC_BMS_RESET in the USER_SETTINGS */
|
Feature is only used if user has enabled PERIODIC_BMS_RESET in the USER_SETTINGS */
|
||||||
|
|
||||||
#ifdef BMS_POWER
|
|
||||||
void handle_BMSpower() {
|
void handle_BMSpower() {
|
||||||
if (periodic_bms_reset || remote_bms_reset) {
|
if (periodic_bms_reset || remote_bms_reset) {
|
||||||
|
auto bms_power_pin = esp32hal->BMS_POWER();
|
||||||
|
|
||||||
// Get current time
|
// Get current time
|
||||||
currentTime = millis();
|
currentTime = millis();
|
||||||
|
|
||||||
|
@ -285,10 +307,7 @@ void handle_BMSpower() {
|
||||||
// If power has been removed for 30 seconds, restore the power
|
// If power has been removed for 30 seconds, restore the power
|
||||||
if (datalayer.system.status.BMS_reset_in_progress && currentTime - lastPowerRemovalTime >= powerRemovalDuration) {
|
if (datalayer.system.status.BMS_reset_in_progress && currentTime - lastPowerRemovalTime >= powerRemovalDuration) {
|
||||||
// Reapply power to the BMS
|
// Reapply power to the BMS
|
||||||
digitalWrite(BMS_POWER, HIGH);
|
digitalWrite(bms_power_pin, HIGH);
|
||||||
#ifdef BMS_2_POWER
|
|
||||||
digitalWrite(BMS_2_POWER, HIGH); // Same for battery 2
|
|
||||||
#endif
|
|
||||||
bmsPowerOnTime = currentTime;
|
bmsPowerOnTime = currentTime;
|
||||||
datalayer.system.status.BMS_reset_in_progress = false; // Reset the power removal flag
|
datalayer.system.status.BMS_reset_in_progress = false; // Reset the power removal flag
|
||||||
datalayer.system.status.BMS_startup_in_progress = true; // Set the BMS warmup flag
|
datalayer.system.status.BMS_startup_in_progress = true; // Set the BMS warmup flag
|
||||||
|
@ -303,10 +322,11 @@ void handle_BMSpower() {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
void start_bms_reset() {
|
void start_bms_reset() {
|
||||||
if (periodic_bms_reset || remote_bms_reset) {
|
if (periodic_bms_reset || remote_bms_reset) {
|
||||||
|
auto bms_power_pin = esp32hal->BMS_POWER();
|
||||||
|
|
||||||
if (!datalayer.system.status.BMS_reset_in_progress) {
|
if (!datalayer.system.status.BMS_reset_in_progress) {
|
||||||
lastPowerRemovalTime = currentTime; // Record the time when BMS reset was started
|
lastPowerRemovalTime = currentTime; // Record the time when BMS reset was started
|
||||||
// we are now resetting at the correct time. We don't need to offset anymore
|
// we are now resetting at the correct time. We don't need to offset anymore
|
||||||
|
@ -319,12 +339,7 @@ void start_bms_reset() {
|
||||||
// We try to keep contactors engaged during this pause, and just ramp power down to 0.
|
// We try to keep contactors engaged during this pause, and just ramp power down to 0.
|
||||||
setBatteryPause(true, false, false, false);
|
setBatteryPause(true, false, false, false);
|
||||||
|
|
||||||
#ifdef BMS_POWER
|
digitalWrite(bms_power_pin, LOW); // Remove power by setting the BMS power pin to LOW
|
||||||
digitalWrite(BMS_POWER, LOW); // Remove power by setting the BMS power pin to LOW
|
|
||||||
#endif
|
|
||||||
#ifdef BMS_2_POWER
|
|
||||||
digitalWrite(BMS_2_POWER, LOW); // Same for battery 2
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -36,9 +36,9 @@ void start_bms_reset();
|
||||||
*
|
*
|
||||||
* @param[in] void
|
* @param[in] void
|
||||||
*
|
*
|
||||||
* @return void
|
* @return true if contactor init was successful, false otherwise.
|
||||||
*/
|
*/
|
||||||
void init_contactors();
|
bool init_contactors();
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Handle contactors
|
* @brief Handle contactors
|
||||||
|
|
|
@ -1,33 +1,45 @@
|
||||||
#include "comm_equipmentstopbutton.h"
|
#include "comm_equipmentstopbutton.h"
|
||||||
#include "../../include.h"
|
#include "../../include.h"
|
||||||
|
|
||||||
|
STOP_BUTTON_BEHAVIOR equipment_stop_behavior = stop_button_default_behavior;
|
||||||
|
|
||||||
// Parameters
|
// Parameters
|
||||||
#ifdef EQUIPMENT_STOP_BUTTON
|
|
||||||
const unsigned long equipment_button_long_press_duration =
|
const unsigned long equipment_button_long_press_duration =
|
||||||
15000; // 15 seconds for long press in case of MOMENTARY_SWITCH
|
15000; // 15 seconds for long press in case of MOMENTARY_SWITCH
|
||||||
const unsigned long equipment_button_debounce_duration = 200; // 200ms for debouncing the button
|
const unsigned long equipment_button_debounce_duration = 200; // 200ms for debouncing the button
|
||||||
unsigned long timeSincePress = 0; // Variable to store the time since the last press
|
unsigned long timeSincePress = 0; // Variable to store the time since the last press
|
||||||
DebouncedButton equipment_stop_button; // Debounced button object
|
DebouncedButton equipment_stop_button; // Debounced button object
|
||||||
#endif // EQUIPMENT_STOP_BUTTON
|
|
||||||
|
|
||||||
// Initialization functions
|
// Initialization functions
|
||||||
#ifdef EQUIPMENT_STOP_BUTTON
|
bool init_equipment_stop_button() {
|
||||||
void init_equipment_stop_button() {
|
if (equipment_stop_behavior == STOP_BUTTON_BEHAVIOR::NOT_CONNECTED) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
auto pin = esp32hal->EQUIPMENT_STOP_PIN();
|
||||||
|
if (!esp32hal->alloc_pins("Equipment stop button", pin)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
//using external pullup resistors NC
|
//using external pullup resistors NC
|
||||||
pinMode(EQUIPMENT_STOP_PIN, INPUT);
|
pinMode(pin, INPUT);
|
||||||
// Initialize the debounced button with NC switch type and equipment_button_debounce_duration debounce time
|
// Initialize the debounced button with NC switch type and equipment_button_debounce_duration debounce time
|
||||||
initDebouncedButton(equipment_stop_button, EQUIPMENT_STOP_PIN, NC, equipment_button_debounce_duration);
|
initDebouncedButton(equipment_stop_button, pin, NC, equipment_button_debounce_duration);
|
||||||
|
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
#endif // EQUIPMENT_STOP_BUTTON
|
|
||||||
|
|
||||||
// Main functions
|
// Main functions
|
||||||
|
|
||||||
#ifdef EQUIPMENT_STOP_BUTTON
|
|
||||||
void monitor_equipment_stop_button() {
|
void monitor_equipment_stop_button() {
|
||||||
|
|
||||||
|
if (equipment_stop_behavior == STOP_BUTTON_BEHAVIOR::NOT_CONNECTED) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
ButtonState changed_state = debounceButton(equipment_stop_button, timeSincePress);
|
ButtonState changed_state = debounceButton(equipment_stop_button, timeSincePress);
|
||||||
|
|
||||||
if (equipment_stop_behavior == LATCHING_SWITCH) {
|
if (equipment_stop_behavior == STOP_BUTTON_BEHAVIOR::LATCHING_SWITCH) {
|
||||||
if (changed_state == PRESSED) {
|
if (changed_state == PRESSED) {
|
||||||
// Changed to ON – initiating equipment stop.
|
// Changed to ON – initiating equipment stop.
|
||||||
setBatteryPause(true, false, true);
|
setBatteryPause(true, false, true);
|
||||||
|
@ -35,7 +47,7 @@ void monitor_equipment_stop_button() {
|
||||||
// Changed to OFF – ending equipment stop.
|
// Changed to OFF – ending equipment stop.
|
||||||
setBatteryPause(false, false, false);
|
setBatteryPause(false, false, false);
|
||||||
}
|
}
|
||||||
} else if (equipment_stop_behavior == MOMENTARY_SWITCH) {
|
} else if (equipment_stop_behavior == STOP_BUTTON_BEHAVIOR::MOMENTARY_SWITCH) {
|
||||||
if (changed_state == RELEASED) { // button is released
|
if (changed_state == RELEASED) { // button is released
|
||||||
|
|
||||||
if (timeSincePress < equipment_button_long_press_duration) {
|
if (timeSincePress < equipment_button_long_press_duration) {
|
||||||
|
@ -48,4 +60,3 @@ void monitor_equipment_stop_button() {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif // EQUIPMENT_STOP_BUTTON
|
|
||||||
|
|
|
@ -1,11 +1,7 @@
|
||||||
#ifndef _COMM_EQUIPMENTSTOPBUTTON_H_
|
#ifndef _COMM_EQUIPMENTSTOPBUTTON_H_
|
||||||
#define _COMM_EQUIPMENTSTOPBUTTON_H_
|
#define _COMM_EQUIPMENTSTOPBUTTON_H_
|
||||||
|
|
||||||
#include "../../include.h"
|
|
||||||
|
|
||||||
#ifdef EQUIPMENT_STOP_BUTTON
|
|
||||||
#include "../../devboard/utils/debounce_button.h"
|
#include "../../devboard/utils/debounce_button.h"
|
||||||
#endif
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Initialization of equipment stop button
|
* @brief Initialization of equipment stop button
|
||||||
|
@ -14,7 +10,7 @@
|
||||||
*
|
*
|
||||||
* @return void
|
* @return void
|
||||||
*/
|
*/
|
||||||
void init_equipment_stop_button();
|
bool init_equipment_stop_button();
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Monitor equipment stop button
|
* @brief Monitor equipment stop button
|
||||||
|
@ -25,4 +21,8 @@ void init_equipment_stop_button();
|
||||||
*/
|
*/
|
||||||
void monitor_equipment_stop_button();
|
void monitor_equipment_stop_button();
|
||||||
|
|
||||||
|
enum class STOP_BUTTON_BEHAVIOR { NOT_CONNECTED = 0, LATCHING_SWITCH = 1, MOMENTARY_SWITCH = 2, Highest };
|
||||||
|
|
||||||
|
extern STOP_BUTTON_BEHAVIOR equipment_stop_behavior;
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -1,4 +1,7 @@
|
||||||
#include "comm_nvm.h"
|
#include "comm_nvm.h"
|
||||||
|
#include "../../communication/can/comm_can.h"
|
||||||
|
#include "../../devboard/mqtt/mqtt.h"
|
||||||
|
#include "../../devboard/wifi/wifi.h"
|
||||||
#include "../../include.h"
|
#include "../../include.h"
|
||||||
#include "../contactorcontrol/comm_contactorcontrol.h"
|
#include "../contactorcontrol/comm_contactorcontrol.h"
|
||||||
|
|
||||||
|
@ -15,6 +18,7 @@ void init_stored_settings() {
|
||||||
// Always get the equipment stop status
|
// Always get the equipment stop status
|
||||||
datalayer.system.settings.equipment_stop_active = settings.getBool("EQUIPMENT_STOP", false);
|
datalayer.system.settings.equipment_stop_active = settings.getBool("EQUIPMENT_STOP", false);
|
||||||
if (datalayer.system.settings.equipment_stop_active) {
|
if (datalayer.system.settings.equipment_stop_active) {
|
||||||
|
DEBUG_PRINTF("Equipment stop status set in boot.");
|
||||||
set_event(EVENT_EQUIPMENT_STOP, 1);
|
set_event(EVENT_EQUIPMENT_STOP, 1);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -25,7 +29,6 @@ void init_stored_settings() {
|
||||||
settings.putBool("EQUIPMENT_STOP", datalayer.system.settings.equipment_stop_active);
|
settings.putBool("EQUIPMENT_STOP", datalayer.system.settings.equipment_stop_active);
|
||||||
#endif // LOAD_SAVED_SETTINGS_ON_BOOT
|
#endif // LOAD_SAVED_SETTINGS_ON_BOOT
|
||||||
|
|
||||||
#ifdef WIFI
|
|
||||||
char tempSSIDstring[63]; // Allocate buffer with sufficient size
|
char tempSSIDstring[63]; // Allocate buffer with sufficient size
|
||||||
size_t lengthSSID = settings.getString("SSID", tempSSIDstring, sizeof(tempSSIDstring));
|
size_t lengthSSID = settings.getString("SSID", tempSSIDstring, sizeof(tempSSIDstring));
|
||||||
if (lengthSSID > 0) { // Successfully read the string from memory. Set it to SSID!
|
if (lengthSSID > 0) { // Successfully read the string from memory. Set it to SSID!
|
||||||
|
@ -38,7 +41,6 @@ void init_stored_settings() {
|
||||||
password = tempPasswordString;
|
password = tempPasswordString;
|
||||||
} else { // Reading from settings failed. Do nothing with SSID. Raise event?
|
} else { // Reading from settings failed. Do nothing with SSID. Raise event?
|
||||||
}
|
}
|
||||||
#endif // WIFI
|
|
||||||
|
|
||||||
temp = settings.getUInt("BATTERY_WH_MAX", false);
|
temp = settings.getUInt("BATTERY_WH_MAX", false);
|
||||||
if (temp != 0) {
|
if (temp != 0) {
|
||||||
|
@ -77,14 +79,56 @@ void init_stored_settings() {
|
||||||
|
|
||||||
#ifdef COMMON_IMAGE
|
#ifdef COMMON_IMAGE
|
||||||
user_selected_battery_type = (BatteryType)settings.getUInt("BATTTYPE", (int)BatteryType::None);
|
user_selected_battery_type = (BatteryType)settings.getUInt("BATTTYPE", (int)BatteryType::None);
|
||||||
|
user_selected_battery_chemistry =
|
||||||
|
(battery_chemistry_enum)settings.getUInt("BATTCHEM", (int)battery_chemistry_enum::NCA);
|
||||||
user_selected_inverter_protocol = (InverterProtocolType)settings.getUInt("INVTYPE", (int)InverterProtocolType::None);
|
user_selected_inverter_protocol = (InverterProtocolType)settings.getUInt("INVTYPE", (int)InverterProtocolType::None);
|
||||||
user_selected_charger_type = (ChargerType)settings.getUInt("CHGTYPE", (int)ChargerType::None);
|
user_selected_charger_type = (ChargerType)settings.getUInt("CHGTYPE", (int)ChargerType::None);
|
||||||
|
user_selected_shunt_type = (ShuntType)settings.getUInt("SHUNTTYPE", (int)ShuntType::None);
|
||||||
|
|
||||||
|
auto readIf = [](const char* settingName) {
|
||||||
|
auto batt1If = (comm_interface)settings.getUInt(settingName, (int)comm_interface::CanNative);
|
||||||
|
switch (batt1If) {
|
||||||
|
case comm_interface::CanNative:
|
||||||
|
return CAN_Interface::CAN_NATIVE;
|
||||||
|
case comm_interface::CanFdNative:
|
||||||
|
return CAN_Interface::CANFD_NATIVE;
|
||||||
|
case comm_interface::CanAddonMcp2515:
|
||||||
|
return CAN_Interface::CAN_ADDON_MCP2515;
|
||||||
|
case comm_interface::CanFdAddonMcp2518:
|
||||||
|
return CAN_Interface::CANFD_ADDON_MCP2518;
|
||||||
|
}
|
||||||
|
|
||||||
|
return CAN_Interface::CAN_NATIVE;
|
||||||
|
};
|
||||||
|
|
||||||
|
can_config.battery = readIf("BATTCOMM");
|
||||||
|
can_config.battery_double = readIf("BATT2COMM");
|
||||||
|
can_config.inverter = readIf("INVCOMM");
|
||||||
|
can_config.charger = readIf("CHGCOMM");
|
||||||
|
can_config.shunt = readIf("SHUNTCOMM");
|
||||||
|
|
||||||
|
equipment_stop_behavior = (STOP_BUTTON_BEHAVIOR)settings.getUInt("EQSTOP", (int)STOP_BUTTON_BEHAVIOR::NOT_CONNECTED);
|
||||||
user_selected_second_battery = settings.getBool("DBLBTR", false);
|
user_selected_second_battery = settings.getBool("DBLBTR", false);
|
||||||
contactor_control_enabled = settings.getBool("CNTCTRL", false);
|
contactor_control_enabled = settings.getBool("CNTCTRL", false);
|
||||||
contactor_control_enabled_double_battery = settings.getBool("CNTCTRLDBL", false);
|
contactor_control_enabled_double_battery = settings.getBool("CNTCTRLDBL", false);
|
||||||
pwm_contactor_control = settings.getBool("PWMCNTCTRL", false);
|
pwm_contactor_control = settings.getBool("PWMCNTCTRL", false);
|
||||||
periodic_bms_reset = settings.getBool("PERBMSRESET", false);
|
periodic_bms_reset = settings.getBool("PERBMSRESET", false);
|
||||||
remote_bms_reset = settings.getBool("REMBMSRESET", false);
|
remote_bms_reset = settings.getBool("REMBMSRESET", false);
|
||||||
|
use_canfd_as_can = settings.getBool("CANFDASCAN", false);
|
||||||
|
|
||||||
|
// WIFI AP is enabled by default unless disabled in the settings
|
||||||
|
wifiap_enabled = settings.getBool("WIFIAPENABLED", true);
|
||||||
|
passwordAP = settings.getString("APPASSWORD", "123456789").c_str();
|
||||||
|
mqtt_enabled = settings.getBool("MQTTENABLED", false);
|
||||||
|
ha_autodiscovery_enabled = settings.getBool("HADISC", false);
|
||||||
|
|
||||||
|
custom_hostname = settings.getString("HOSTNAME").c_str();
|
||||||
|
|
||||||
|
mqtt_server = settings.getString("MQTTSERVER").c_str();
|
||||||
|
mqtt_port = settings.getUInt("MQTTPORT", 0);
|
||||||
|
mqtt_user = settings.getString("MQTTUSER").c_str();
|
||||||
|
mqtt_password = settings.getString("MQTTPASSWORD").c_str();
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
settings.end();
|
settings.end();
|
||||||
|
@ -103,14 +147,12 @@ void store_settings() {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef WIFI
|
|
||||||
if (!settings.putString("SSID", String(ssid.c_str()))) {
|
if (!settings.putString("SSID", String(ssid.c_str()))) {
|
||||||
set_event(EVENT_PERSISTENT_SAVE_INFO, 1);
|
set_event(EVENT_PERSISTENT_SAVE_INFO, 1);
|
||||||
}
|
}
|
||||||
if (!settings.putString("PASSWORD", String(password.c_str()))) {
|
if (!settings.putString("PASSWORD", String(password.c_str()))) {
|
||||||
set_event(EVENT_PERSISTENT_SAVE_INFO, 2);
|
set_event(EVENT_PERSISTENT_SAVE_INFO, 2);
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
if (!settings.putUInt("BATTERY_WH_MAX", datalayer.battery.info.total_capacity_Wh)) {
|
if (!settings.putUInt("BATTERY_WH_MAX", datalayer.battery.info.total_capacity_Wh)) {
|
||||||
set_event(EVENT_PERSISTENT_SAVE_INFO, 3);
|
set_event(EVENT_PERSISTENT_SAVE_INFO, 3);
|
||||||
|
|
|
@ -3,8 +3,10 @@
|
||||||
|
|
||||||
#include "../../include.h"
|
#include "../../include.h"
|
||||||
|
|
||||||
|
#include <limits>
|
||||||
#include "../../datalayer/datalayer.h"
|
#include "../../datalayer/datalayer.h"
|
||||||
#include "../../devboard/utils/events.h"
|
#include "../../devboard/utils/events.h"
|
||||||
|
#include "../../devboard/utils/logging.h"
|
||||||
#include "../../devboard/wifi/wifi.h"
|
#include "../../devboard/wifi/wifi.h"
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -46,16 +48,48 @@ class BatteryEmulatorSettingsStore {
|
||||||
|
|
||||||
~BatteryEmulatorSettingsStore() { settings.end(); }
|
~BatteryEmulatorSettingsStore() { settings.end(); }
|
||||||
|
|
||||||
|
void clearAll() {
|
||||||
|
settings.clear();
|
||||||
|
settingsUpdated = true;
|
||||||
|
}
|
||||||
|
|
||||||
uint32_t getUInt(const char* name, uint32_t defaultValue) { return settings.getUInt(name, defaultValue); }
|
uint32_t getUInt(const char* name, uint32_t defaultValue) { return settings.getUInt(name, defaultValue); }
|
||||||
|
|
||||||
void saveUInt(const char* name, uint32_t value) { settings.putUInt(name, value); }
|
void saveUInt(const char* name, uint32_t value) {
|
||||||
|
auto oldValue = settings.getUInt(name, std::numeric_limits<uint32_t>::max());
|
||||||
|
settings.putUInt(name, value);
|
||||||
|
settingsUpdated = settingsUpdated || value != oldValue;
|
||||||
|
}
|
||||||
|
|
||||||
bool getBool(const char* name) { return settings.getBool(name, false); }
|
bool settingExists(const char* name) { return settings.isKey(name); }
|
||||||
|
|
||||||
void saveBool(const char* name, bool value) { settings.putBool(name, value); }
|
bool getBool(const char* name, bool defaultValue = false) { return settings.getBool(name, defaultValue); }
|
||||||
|
|
||||||
|
void saveBool(const char* name, bool value) {
|
||||||
|
auto oldValue = settings.getBool(name, false);
|
||||||
|
settings.putBool(name, value);
|
||||||
|
settingsUpdated = settingsUpdated || value != oldValue;
|
||||||
|
}
|
||||||
|
|
||||||
|
String getString(const char* name) { return settings.getString(name, String()); }
|
||||||
|
|
||||||
|
String getString(const char* name, const char* defaultValue) {
|
||||||
|
return settings.getString(name, String(defaultValue));
|
||||||
|
}
|
||||||
|
|
||||||
|
void saveString(const char* name, const char* value) {
|
||||||
|
auto oldValue = settings.getString(name);
|
||||||
|
settings.putString(name, value);
|
||||||
|
settingsUpdated = settingsUpdated || String(value) != oldValue;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool were_settings_updated() const { return settingsUpdated; }
|
||||||
|
|
||||||
private:
|
private:
|
||||||
Preferences settings;
|
Preferences settings;
|
||||||
|
|
||||||
|
// To track if settings were updated
|
||||||
|
bool settingsUpdated = false;
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -2,7 +2,15 @@
|
||||||
#include "../../datalayer/datalayer.h"
|
#include "../../datalayer/datalayer.h"
|
||||||
#include "../../datalayer/datalayer_extended.h"
|
#include "../../datalayer/datalayer_extended.h"
|
||||||
#include "../../include.h"
|
#include "../../include.h"
|
||||||
|
|
||||||
#ifdef PRECHARGE_CONTROL
|
#ifdef PRECHARGE_CONTROL
|
||||||
|
const bool precharge_control_enabled_default = true;
|
||||||
|
#else
|
||||||
|
const bool precharge_control_enabled_default = false;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
bool precharge_control_enabled = precharge_control_enabled_default;
|
||||||
|
|
||||||
// Parameters
|
// Parameters
|
||||||
#define MAX_PRECHARGE_TIME_MS 15000 // Maximum time precharge may be enabled
|
#define MAX_PRECHARGE_TIME_MS 15000 // Maximum time precharge may be enabled
|
||||||
#define Precharge_default_PWM_Freq 11000
|
#define Precharge_default_PWM_Freq 11000
|
||||||
|
@ -25,19 +33,36 @@ static int32_t prev_external_voltage = 20000;
|
||||||
|
|
||||||
// Initialization functions
|
// Initialization functions
|
||||||
|
|
||||||
void init_precharge_control() {
|
bool init_precharge_control() {
|
||||||
|
if (!precharge_control_enabled) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
// Setup PWM Channel Frequency and Resolution
|
// Setup PWM Channel Frequency and Resolution
|
||||||
#ifdef DEBUG_LOG
|
#ifdef DEBUG_LOG
|
||||||
logging.printf("Precharge control initialised\n");
|
logging.printf("Precharge control initialised\n");
|
||||||
#endif
|
#endif
|
||||||
pinMode(HIA4V1_PIN, OUTPUT);
|
|
||||||
digitalWrite(HIA4V1_PIN, LOW);
|
auto hia4v1_pin = esp32hal->HIA4V1_PIN();
|
||||||
pinMode(INVERTER_DISCONNECT_CONTACTOR_PIN, OUTPUT);
|
auto inverter_disconnect_contactor_pin = esp32hal->INVERTER_DISCONNECT_CONTACTOR_PIN();
|
||||||
digitalWrite(INVERTER_DISCONNECT_CONTACTOR_PIN, LOW);
|
|
||||||
|
if (!esp32hal->alloc_pins("Precharge control", hia4v1_pin, inverter_disconnect_contactor_pin)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
pinMode(hia4v1_pin, OUTPUT);
|
||||||
|
digitalWrite(hia4v1_pin, LOW);
|
||||||
|
pinMode(inverter_disconnect_contactor_pin, OUTPUT);
|
||||||
|
digitalWrite(inverter_disconnect_contactor_pin, LOW);
|
||||||
|
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Main functions
|
// Main functions
|
||||||
void handle_precharge_control(unsigned long currentMillis) {
|
void handle_precharge_control(unsigned long currentMillis) {
|
||||||
|
auto hia4v1_pin = esp32hal->HIA4V1_PIN();
|
||||||
|
auto inverter_disconnect_contactor_pin = esp32hal->INVERTER_DISCONNECT_CONTACTOR_PIN();
|
||||||
|
|
||||||
int32_t target_voltage = datalayer.battery.status.voltage_dV;
|
int32_t target_voltage = datalayer.battery.status.voltage_dV;
|
||||||
int32_t external_voltage = datalayer_extended.meb.BMS_voltage_intermediate_dV;
|
int32_t external_voltage = datalayer_extended.meb.BMS_voltage_intermediate_dV;
|
||||||
|
|
||||||
|
@ -49,14 +74,14 @@ void handle_precharge_control(unsigned long currentMillis) {
|
||||||
break;
|
break;
|
||||||
case AUTO_PRECHARGE_START:
|
case AUTO_PRECHARGE_START:
|
||||||
freq = Precharge_default_PWM_Freq;
|
freq = Precharge_default_PWM_Freq;
|
||||||
ledcAttachChannel(HIA4V1_PIN, freq, Precharge_PWM_Res, PWM_Precharge_Channel);
|
ledcAttachChannel(hia4v1_pin, freq, Precharge_PWM_Res, PWM_Precharge_Channel);
|
||||||
ledcWriteTone(HIA4V1_PIN, freq); // Set frequency and set dutycycle to 50%
|
ledcWriteTone(hia4v1_pin, freq); // Set frequency and set dutycycle to 50%
|
||||||
prechargeStartTime = currentMillis;
|
prechargeStartTime = currentMillis;
|
||||||
datalayer.system.status.precharge_status = AUTO_PRECHARGE_PRECHARGING;
|
datalayer.system.status.precharge_status = AUTO_PRECHARGE_PRECHARGING;
|
||||||
#ifdef DEBUG_LOG
|
#ifdef DEBUG_LOG
|
||||||
logging.printf("Precharge: Starting sequence\n");
|
logging.printf("Precharge: Starting sequence\n");
|
||||||
#endif
|
#endif
|
||||||
digitalWrite(INVERTER_DISCONNECT_CONTACTOR_PIN, OFF);
|
digitalWrite(inverter_disconnect_contactor_pin, OFF);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case AUTO_PRECHARGE_PRECHARGING:
|
case AUTO_PRECHARGE_PRECHARGING:
|
||||||
|
@ -84,24 +109,24 @@ void handle_precharge_control(unsigned long currentMillis) {
|
||||||
logging.printf("Precharge: Target: %d V Extern: %d V Frequency: %u\n", target_voltage / 10,
|
logging.printf("Precharge: Target: %d V Extern: %d V Frequency: %u\n", target_voltage / 10,
|
||||||
external_voltage / 10, freq);
|
external_voltage / 10, freq);
|
||||||
#endif
|
#endif
|
||||||
ledcWriteTone(HIA4V1_PIN, freq);
|
ledcWriteTone(hia4v1_pin, freq);
|
||||||
}
|
}
|
||||||
|
|
||||||
if ((datalayer.battery.status.real_bms_status != BMS_STANDBY &&
|
if ((datalayer.battery.status.real_bms_status != BMS_STANDBY &&
|
||||||
datalayer.battery.status.real_bms_status != BMS_ACTIVE) ||
|
datalayer.battery.status.real_bms_status != BMS_ACTIVE) ||
|
||||||
datalayer.battery.status.bms_status != ACTIVE || datalayer.system.settings.equipment_stop_active) {
|
datalayer.battery.status.bms_status != ACTIVE || datalayer.system.settings.equipment_stop_active) {
|
||||||
pinMode(HIA4V1_PIN, OUTPUT);
|
pinMode(hia4v1_pin, OUTPUT);
|
||||||
digitalWrite(HIA4V1_PIN, LOW);
|
digitalWrite(hia4v1_pin, LOW);
|
||||||
digitalWrite(INVERTER_DISCONNECT_CONTACTOR_PIN, ON);
|
digitalWrite(inverter_disconnect_contactor_pin, ON);
|
||||||
datalayer.system.status.precharge_status = AUTO_PRECHARGE_IDLE;
|
datalayer.system.status.precharge_status = AUTO_PRECHARGE_IDLE;
|
||||||
#ifdef DEBUG_LOG
|
#ifdef DEBUG_LOG
|
||||||
logging.printf("Precharge: Disabling Precharge bms not standby/active or equipment stop\n");
|
logging.printf("Precharge: Disabling Precharge bms not standby/active or equipment stop\n");
|
||||||
#endif
|
#endif
|
||||||
} else if (currentMillis - prechargeStartTime >= MAX_PRECHARGE_TIME_MS ||
|
} else if (currentMillis - prechargeStartTime >= MAX_PRECHARGE_TIME_MS ||
|
||||||
datalayer.battery.status.real_bms_status == BMS_FAULT) {
|
datalayer.battery.status.real_bms_status == BMS_FAULT) {
|
||||||
pinMode(HIA4V1_PIN, OUTPUT);
|
pinMode(hia4v1_pin, OUTPUT);
|
||||||
digitalWrite(HIA4V1_PIN, LOW);
|
digitalWrite(hia4v1_pin, LOW);
|
||||||
digitalWrite(INVERTER_DISCONNECT_CONTACTOR_PIN, ON);
|
digitalWrite(inverter_disconnect_contactor_pin, ON);
|
||||||
datalayer.system.status.precharge_status = AUTO_PRECHARGE_OFF;
|
datalayer.system.status.precharge_status = AUTO_PRECHARGE_OFF;
|
||||||
#ifdef DEBUG_LOG
|
#ifdef DEBUG_LOG
|
||||||
logging.printf("Precharge: Disabled (timeout reached / BMS fault) -> AUTO_PRECHARGE_OFF\n");
|
logging.printf("Precharge: Disabled (timeout reached / BMS fault) -> AUTO_PRECHARGE_OFF\n");
|
||||||
|
@ -110,9 +135,9 @@ void handle_precharge_control(unsigned long currentMillis) {
|
||||||
|
|
||||||
// Add event
|
// Add event
|
||||||
} else if (datalayer.system.status.battery_allows_contactor_closing) {
|
} else if (datalayer.system.status.battery_allows_contactor_closing) {
|
||||||
pinMode(HIA4V1_PIN, OUTPUT);
|
pinMode(hia4v1_pin, OUTPUT);
|
||||||
digitalWrite(HIA4V1_PIN, LOW);
|
digitalWrite(hia4v1_pin, LOW);
|
||||||
digitalWrite(INVERTER_DISCONNECT_CONTACTOR_PIN, ON);
|
digitalWrite(inverter_disconnect_contactor_pin, ON);
|
||||||
datalayer.system.status.precharge_status = AUTO_PRECHARGE_COMPLETED;
|
datalayer.system.status.precharge_status = AUTO_PRECHARGE_COMPLETED;
|
||||||
#ifdef DEBUG_LOG
|
#ifdef DEBUG_LOG
|
||||||
logging.printf("Precharge: Disabled (contacts closed) -> COMPLETED\n");
|
logging.printf("Precharge: Disabled (contacts closed) -> COMPLETED\n");
|
||||||
|
@ -134,8 +159,8 @@ void handle_precharge_control(unsigned long currentMillis) {
|
||||||
!datalayer.system.status.inverter_allows_contactor_closing ||
|
!datalayer.system.status.inverter_allows_contactor_closing ||
|
||||||
datalayer.system.settings.equipment_stop_active || datalayer.battery.status.bms_status != FAULT) {
|
datalayer.system.settings.equipment_stop_active || datalayer.battery.status.bms_status != FAULT) {
|
||||||
datalayer.system.status.precharge_status = AUTO_PRECHARGE_IDLE;
|
datalayer.system.status.precharge_status = AUTO_PRECHARGE_IDLE;
|
||||||
pinMode(HIA4V1_PIN, OUTPUT);
|
pinMode(hia4v1_pin, OUTPUT);
|
||||||
digitalWrite(HIA4V1_PIN, LOW);
|
digitalWrite(hia4v1_pin, LOW);
|
||||||
#ifdef DEBUG_LOG
|
#ifdef DEBUG_LOG
|
||||||
logging.printf("Precharge: equipment stop activated -> IDLE\n");
|
logging.printf("Precharge: equipment stop activated -> IDLE\n");
|
||||||
#endif
|
#endif
|
||||||
|
@ -146,4 +171,3 @@ void handle_precharge_control(unsigned long currentMillis) {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif // PRECHARGE_CONTROL
|
|
||||||
|
|
|
@ -12,7 +12,7 @@
|
||||||
*
|
*
|
||||||
* @return void
|
* @return void
|
||||||
*/
|
*/
|
||||||
void init_precharge_control();
|
bool init_precharge_control();
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Handle contactors
|
* @brief Handle contactors
|
||||||
|
|
|
@ -3,22 +3,35 @@
|
||||||
|
|
||||||
#include <list>
|
#include <list>
|
||||||
|
|
||||||
void init_rs485() {
|
bool init_rs485() {
|
||||||
#ifdef RS485_EN_PIN
|
|
||||||
pinMode(RS485_EN_PIN, OUTPUT);
|
auto en_pin = esp32hal->RS485_EN_PIN();
|
||||||
digitalWrite(RS485_EN_PIN, HIGH);
|
auto se_pin = esp32hal->RS485_SE_PIN();
|
||||||
#endif // RS485_EN_PIN
|
auto pin_5v_en = esp32hal->PIN_5V_EN();
|
||||||
#ifdef RS485_SE_PIN
|
|
||||||
pinMode(RS485_SE_PIN, OUTPUT);
|
if (!esp32hal->alloc_pins_ignore_unused("RS485", en_pin, se_pin, pin_5v_en)) {
|
||||||
digitalWrite(RS485_SE_PIN, HIGH);
|
return false;
|
||||||
#endif // RS485_SE_PIN
|
}
|
||||||
#ifdef PIN_5V_EN
|
|
||||||
pinMode(PIN_5V_EN, OUTPUT);
|
if (en_pin != GPIO_NUM_NC) {
|
||||||
digitalWrite(PIN_5V_EN, HIGH);
|
pinMode(en_pin, OUTPUT);
|
||||||
#endif // PIN_5V_EN
|
digitalWrite(en_pin, HIGH);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (se_pin != GPIO_NUM_NC) {
|
||||||
|
pinMode(se_pin, OUTPUT);
|
||||||
|
digitalWrite(se_pin, HIGH);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (pin_5v_en != GPIO_NUM_NC) {
|
||||||
|
pinMode(pin_5v_en, OUTPUT);
|
||||||
|
digitalWrite(pin_5v_en, HIGH);
|
||||||
|
}
|
||||||
|
|
||||||
// Inverters and batteries are expected to initialize their serial port in their setup-function
|
// Inverters and batteries are expected to initialize their serial port in their setup-function
|
||||||
// for RS485 or Modbus comms.
|
// for RS485 or Modbus comms.
|
||||||
|
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
static std::list<Rs485Receiver*> receivers;
|
static std::list<Rs485Receiver*> receivers;
|
||||||
|
|
|
@ -6,9 +6,9 @@
|
||||||
*
|
*
|
||||||
* @param[in] void
|
* @param[in] void
|
||||||
*
|
*
|
||||||
* @return void
|
* @return true if init was successful, false otherwise.
|
||||||
*/
|
*/
|
||||||
void init_rs485();
|
bool init_rs485();
|
||||||
|
|
||||||
// Defines an interface for any object that needs to receive a signal to handle RS485 comm.
|
// Defines an interface for any object that needs to receive a signal to handle RS485 comm.
|
||||||
// Can be extended later for more complex operation.
|
// Can be extended later for more complex operation.
|
||||||
|
|
|
@ -230,8 +230,6 @@ typedef struct {
|
||||||
float CPU_temperature = 0;
|
float CPU_temperature = 0;
|
||||||
/** array with type of battery used, for displaying on webserver */
|
/** array with type of battery used, for displaying on webserver */
|
||||||
char battery_protocol[64] = {0};
|
char battery_protocol[64] = {0};
|
||||||
/** array with type of inverter protocol used, for displaying on webserver */
|
|
||||||
char inverter_protocol[64] = {0};
|
|
||||||
/** array with type of battery used, for displaying on webserver */
|
/** array with type of battery used, for displaying on webserver */
|
||||||
char shunt_protocol[64] = {0};
|
char shunt_protocol[64] = {0};
|
||||||
/** array with type of inverter brand used, for displaying on webserver */
|
/** array with type of inverter brand used, for displaying on webserver */
|
||||||
|
|
30
Software/src/devboard/hal/hal.cpp
Normal file
30
Software/src/devboard/hal/hal.cpp
Normal file
|
@ -0,0 +1,30 @@
|
||||||
|
#include "hal.h"
|
||||||
|
|
||||||
|
#include "../../../USER_SETTINGS.h"
|
||||||
|
|
||||||
|
#include "hw_3LB.h"
|
||||||
|
#include "hw_devkit.h"
|
||||||
|
#include "hw_lilygo.h"
|
||||||
|
#include "hw_stark.h"
|
||||||
|
|
||||||
|
Esp32Hal* esp32hal = nullptr;
|
||||||
|
|
||||||
|
void init_hal() {
|
||||||
|
#if defined(HW_LILYGO)
|
||||||
|
esp32hal = new LilyGoHal();
|
||||||
|
#elif defined(HW_STARK)
|
||||||
|
esp32hal = new StarkHal();
|
||||||
|
#elif defined(HW_3LB)
|
||||||
|
esp32hal = new ThreeLBHal();
|
||||||
|
#elif defined(HW_DEVKIT)
|
||||||
|
esp32hal = new DevKitHal();
|
||||||
|
#else
|
||||||
|
#error "No HW defined."
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
unsigned long millis();
|
||||||
|
|
||||||
|
bool Esp32Hal::system_booted_up() {
|
||||||
|
return milliseconds(millis()) > BOOTUP_TIME();
|
||||||
|
}
|
|
@ -1,16 +1,167 @@
|
||||||
#ifndef _HAL_H_
|
#ifndef _HAL_H_
|
||||||
#define _HAL_H_
|
#define _HAL_H_
|
||||||
|
|
||||||
#include "../../../USER_SETTINGS.h"
|
#include <soc/gpio_num.h>
|
||||||
|
#include <chrono>
|
||||||
|
#include <unordered_map>
|
||||||
|
#include "../../../src/devboard/utils/events.h"
|
||||||
|
#include "../../../src/devboard/utils/logging.h"
|
||||||
|
#include "../../../src/devboard/utils/types.h"
|
||||||
|
|
||||||
#if defined(HW_LILYGO)
|
// Hardware Abstraction Layer base class.
|
||||||
#include "hw_lilygo.h"
|
// Derive a class to define board-specific parameters such as GPIO pin numbers
|
||||||
#elif defined(HW_STARK)
|
// This base class implements a mechanism for allocating GPIOs.
|
||||||
#include "hw_stark.h"
|
class Esp32Hal {
|
||||||
#elif defined(HW_3LB)
|
public:
|
||||||
#include "hw_3LB.h"
|
virtual const char* name() = 0;
|
||||||
#elif defined(HW_DEVKIT)
|
|
||||||
#include "hw_devkit.h"
|
// Time it takes before system is considered fully started up.
|
||||||
#endif
|
virtual duration BOOTUP_TIME() { return milliseconds(1000); }
|
||||||
|
virtual bool system_booted_up();
|
||||||
|
|
||||||
|
// Core assignment
|
||||||
|
virtual int CORE_FUNCTION_CORE() { return 1; }
|
||||||
|
virtual int MODBUS_CORE() { return 0; }
|
||||||
|
virtual int WIFICORE() { return 0; }
|
||||||
|
|
||||||
|
template <typename... Pins>
|
||||||
|
bool alloc_pins(const char* name, Pins... pins) {
|
||||||
|
std::vector<gpio_num_t> requested_pins = {static_cast<gpio_num_t>(pins)...};
|
||||||
|
|
||||||
|
for (gpio_num_t pin : requested_pins) {
|
||||||
|
if (pin < 0) {
|
||||||
|
set_event(EVENT_GPIO_NOT_DEFINED, (int)pin);
|
||||||
|
allocator_name = name;
|
||||||
|
DEBUG_PRINTF("%s attempted to allocate pin %d that wasn't defined for the selected HW.\n", name, (int)pin);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
auto it = allocated_pins.find(pin);
|
||||||
|
if (it != allocated_pins.end()) {
|
||||||
|
allocator_name = name;
|
||||||
|
allocated_name = it->second.c_str();
|
||||||
|
DEBUG_PRINTF("GPIO conflict for pin %d between %s and %s.\n", (int)pin, name, it->second.c_str());
|
||||||
|
set_event(EVENT_GPIO_CONFLICT, (int)pin);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
for (gpio_num_t pin : requested_pins) {
|
||||||
|
allocated_pins[pin] = name;
|
||||||
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Helper to forward vector to variadic template
|
||||||
|
template <typename Vec, size_t... Is>
|
||||||
|
bool alloc_pins_from_vector(const char* name, const Vec& pins, std::index_sequence<Is...>) {
|
||||||
|
return alloc_pins(name, pins[Is]...);
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename... Pins>
|
||||||
|
bool alloc_pins_ignore_unused(const char* name, Pins... pins) {
|
||||||
|
std::vector<gpio_num_t> valid_pins;
|
||||||
|
for (gpio_num_t pin : std::vector<gpio_num_t>{static_cast<gpio_num_t>(pins)...}) {
|
||||||
|
if (pin != GPIO_NUM_NC) {
|
||||||
|
valid_pins.push_back(pin);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return alloc_pins_from_vector(name, valid_pins, std::make_index_sequence<sizeof...(pins)>{});
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual bool always_enable_bms_power() { return false; }
|
||||||
|
|
||||||
|
virtual gpio_num_t PIN_5V_EN() { return GPIO_NUM_NC; }
|
||||||
|
virtual gpio_num_t RS485_EN_PIN() { return GPIO_NUM_NC; }
|
||||||
|
virtual gpio_num_t RS485_TX_PIN() { return GPIO_NUM_NC; }
|
||||||
|
virtual gpio_num_t RS485_RX_PIN() { return GPIO_NUM_NC; }
|
||||||
|
virtual gpio_num_t RS485_SE_PIN() { return GPIO_NUM_NC; }
|
||||||
|
|
||||||
|
virtual gpio_num_t CAN_TX_PIN() { return GPIO_NUM_NC; }
|
||||||
|
virtual gpio_num_t CAN_RX_PIN() { return GPIO_NUM_NC; }
|
||||||
|
virtual gpio_num_t CAN_SE_PIN() { return GPIO_NUM_NC; }
|
||||||
|
|
||||||
|
// CAN_ADDON
|
||||||
|
// SCK input of MCP2515
|
||||||
|
virtual gpio_num_t MCP2515_SCK() { return GPIO_NUM_NC; }
|
||||||
|
// SDI input of MCP2515
|
||||||
|
virtual gpio_num_t MCP2515_MOSI() { return GPIO_NUM_NC; }
|
||||||
|
// SDO output of MCP2515
|
||||||
|
virtual gpio_num_t MCP2515_MISO() { return GPIO_NUM_NC; }
|
||||||
|
// CS input of MCP2515
|
||||||
|
virtual gpio_num_t MCP2515_CS() { return GPIO_NUM_NC; }
|
||||||
|
// INT output of MCP2515
|
||||||
|
virtual gpio_num_t MCP2515_INT() { return GPIO_NUM_NC; }
|
||||||
|
|
||||||
|
// CANFD_ADDON defines for MCP2517
|
||||||
|
virtual gpio_num_t MCP2517_SCK() { return GPIO_NUM_NC; }
|
||||||
|
virtual gpio_num_t MCP2517_SDI() { return GPIO_NUM_NC; }
|
||||||
|
virtual gpio_num_t MCP2517_SDO() { return GPIO_NUM_NC; }
|
||||||
|
virtual gpio_num_t MCP2517_CS() { return GPIO_NUM_NC; }
|
||||||
|
virtual gpio_num_t MCP2517_INT() { return GPIO_NUM_NC; }
|
||||||
|
|
||||||
|
// CHAdeMO support pin dependencies
|
||||||
|
virtual gpio_num_t CHADEMO_PIN_2() { return GPIO_NUM_NC; }
|
||||||
|
virtual gpio_num_t CHADEMO_PIN_10() { return GPIO_NUM_NC; }
|
||||||
|
virtual gpio_num_t CHADEMO_PIN_7() { return GPIO_NUM_NC; }
|
||||||
|
virtual gpio_num_t CHADEMO_PIN_4() { return GPIO_NUM_NC; }
|
||||||
|
virtual gpio_num_t CHADEMO_LOCK() { return GPIO_NUM_NC; }
|
||||||
|
|
||||||
|
// Contactor handling
|
||||||
|
virtual gpio_num_t POSITIVE_CONTACTOR_PIN() { return GPIO_NUM_NC; }
|
||||||
|
virtual gpio_num_t NEGATIVE_CONTACTOR_PIN() { return GPIO_NUM_NC; }
|
||||||
|
virtual gpio_num_t PRECHARGE_PIN() { return GPIO_NUM_NC; }
|
||||||
|
virtual gpio_num_t BMS_POWER() { return GPIO_NUM_NC; }
|
||||||
|
virtual gpio_num_t SECOND_BATTERY_CONTACTORS_PIN() { return GPIO_NUM_NC; }
|
||||||
|
|
||||||
|
// Automatic precharging
|
||||||
|
virtual gpio_num_t HIA4V1_PIN() { return GPIO_NUM_NC; }
|
||||||
|
virtual gpio_num_t INVERTER_DISCONNECT_CONTACTOR_PIN() { return GPIO_NUM_NC; }
|
||||||
|
|
||||||
|
// SMA CAN contactor pins
|
||||||
|
virtual gpio_num_t INVERTER_CONTACTOR_ENABLE_PIN() { return GPIO_NUM_NC; }
|
||||||
|
|
||||||
|
virtual gpio_num_t INVERTER_CONTACTOR_ENABLE_LED_PIN() { return GPIO_NUM_NC; }
|
||||||
|
|
||||||
|
// SD card
|
||||||
|
virtual gpio_num_t SD_MISO_PIN() { return GPIO_NUM_NC; }
|
||||||
|
virtual gpio_num_t SD_MOSI_PIN() { return GPIO_NUM_NC; }
|
||||||
|
virtual gpio_num_t SD_SCLK_PIN() { return GPIO_NUM_NC; }
|
||||||
|
virtual gpio_num_t SD_CS_PIN() { return GPIO_NUM_NC; }
|
||||||
|
|
||||||
|
// LED
|
||||||
|
virtual gpio_num_t LED_PIN() { return GPIO_NUM_NC; }
|
||||||
|
virtual uint8_t LED_MAX_BRIGHTNESS() { return 40; }
|
||||||
|
|
||||||
|
// Equipment stop pin
|
||||||
|
virtual gpio_num_t EQUIPMENT_STOP_PIN() { return GPIO_NUM_NC; }
|
||||||
|
|
||||||
|
// Battery wake up pins
|
||||||
|
virtual gpio_num_t WUP_PIN1() { return GPIO_NUM_NC; }
|
||||||
|
virtual gpio_num_t WUP_PIN2() { return GPIO_NUM_NC; }
|
||||||
|
|
||||||
|
// Returns the available comm interfaces on this HW
|
||||||
|
virtual std::vector<comm_interface> available_interfaces() = 0;
|
||||||
|
|
||||||
|
String failed_allocator() { return allocator_name; }
|
||||||
|
String conflicting_allocator() { return allocated_name; }
|
||||||
|
|
||||||
|
private:
|
||||||
|
std::unordered_map<gpio_num_t, std::string> allocated_pins;
|
||||||
|
|
||||||
|
// For event logging, store the name of the allocator/allocated
|
||||||
|
// for failed gpio allocations.
|
||||||
|
String allocator_name;
|
||||||
|
String allocated_name;
|
||||||
|
};
|
||||||
|
|
||||||
|
extern Esp32Hal* esp32hal;
|
||||||
|
|
||||||
|
// Needed for AsyncTCPSock library.
|
||||||
|
#define WIFI_CORE (esp32hal->WIFICORE())
|
||||||
|
|
||||||
|
void init_hal();
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -1,115 +1,79 @@
|
||||||
#ifndef __HW_3LB_H__
|
#ifndef __HW_3LB_H__
|
||||||
#define __HW_3LB_H__
|
#define __HW_3LB_H__
|
||||||
|
|
||||||
// Board boot-up time
|
#include "hal.h"
|
||||||
#define BOOTUP_TIME 1000 // Time in ms it takes before system is considered fully started up
|
|
||||||
|
|
||||||
// Core assignment
|
class ThreeLBHal : public Esp32Hal {
|
||||||
#define CORE_FUNCTION_CORE 1
|
public:
|
||||||
#define MODBUS_CORE 0
|
const char* name() { return "3LB board"; }
|
||||||
#define WIFI_CORE 0
|
|
||||||
|
|
||||||
// RS485
|
virtual gpio_num_t RS485_TX_PIN() { return GPIO_NUM_1; }
|
||||||
//#define PIN_5V_EN 16
|
virtual gpio_num_t RS485_RX_PIN() { return GPIO_NUM_3; }
|
||||||
//#define RS485_EN_PIN 17 // 17 /RE
|
|
||||||
#define RS485_TX_PIN 1 // 21
|
|
||||||
#define RS485_RX_PIN 3 // 22
|
|
||||||
//#define RS485_SE_PIN 19 // 22 /SHDN
|
|
||||||
|
|
||||||
// CAN settings. CAN_2 is not defined as it can be either MCP2515 or MCP2517, defined by the user settings
|
virtual gpio_num_t CAN_TX_PIN() { return GPIO_NUM_27; }
|
||||||
#define CAN_1_TYPE ESP32CAN
|
virtual gpio_num_t CAN_RX_PIN() { return GPIO_NUM_26; }
|
||||||
|
|
||||||
// CAN1 PIN mappings, do not change these unless you are adding on extra hardware to the PCB
|
// CAN_ADDON
|
||||||
#define CAN_TX_PIN GPIO_NUM_27
|
// SCK input of MCP2515
|
||||||
#define CAN_RX_PIN GPIO_NUM_26
|
virtual gpio_num_t MCP2515_SCK() { return GPIO_NUM_12; }
|
||||||
//#define CAN_SE_PIN 23
|
// SDI input of MCP2515
|
||||||
|
virtual gpio_num_t MCP2515_MOSI() { return GPIO_NUM_5; }
|
||||||
|
// SDO output of MCP2515
|
||||||
|
virtual gpio_num_t MCP2515_MISO() { return GPIO_NUM_34; }
|
||||||
|
// CS input of MCP2515
|
||||||
|
virtual gpio_num_t MCP2515_CS() { return GPIO_NUM_18; }
|
||||||
|
// INT output of MCP2515
|
||||||
|
virtual gpio_num_t MCP2515_INT() { return GPIO_NUM_35; }
|
||||||
|
|
||||||
// CAN2 defines below
|
// CANFD_ADDON defines for MCP2517
|
||||||
|
virtual gpio_num_t MCP2517_SCK() { return GPIO_NUM_17; }
|
||||||
|
virtual gpio_num_t MCP2517_SDI() { return GPIO_NUM_23; }
|
||||||
|
virtual gpio_num_t MCP2517_SDO() { return GPIO_NUM_39; }
|
||||||
|
virtual gpio_num_t MCP2517_CS() { return GPIO_NUM_21; }
|
||||||
|
virtual gpio_num_t MCP2517_INT() { return GPIO_NUM_34; }
|
||||||
|
|
||||||
// CAN_ADDON defines
|
// CHAdeMO support pin dependencies
|
||||||
#define MCP2515_SCK 12 // SCK input of MCP2515
|
virtual gpio_num_t CHADEMO_PIN_2() { return GPIO_NUM_12; }
|
||||||
#define MCP2515_MOSI 5 // SDI input of MCP2515
|
virtual gpio_num_t CHADEMO_PIN_10() { return GPIO_NUM_5; }
|
||||||
#define MCP2515_MISO 34 // SDO output of MCP2515 | Pin 34 is input only, without pullup/down resistors
|
virtual gpio_num_t CHADEMO_PIN_7() { return GPIO_NUM_34; }
|
||||||
#define MCP2515_CS 18 // CS input of MCP2515
|
virtual gpio_num_t CHADEMO_PIN_4() { return GPIO_NUM_35; }
|
||||||
#define MCP2515_INT 35 // INT output of MCP2515 | | Pin 35 is input only, without pullup/down resistors
|
virtual gpio_num_t CHADEMO_LOCK() { return GPIO_NUM_18; }
|
||||||
|
|
||||||
// CANFD_ADDON defines
|
// Contactor handling
|
||||||
#define MCP2517_SCK 17 // SCK input of MCP2517
|
virtual gpio_num_t POSITIVE_CONTACTOR_PIN() { return GPIO_NUM_32; }
|
||||||
#define MCP2517_SDI 23 // SDI input of MCP2517
|
virtual gpio_num_t NEGATIVE_CONTACTOR_PIN() { return GPIO_NUM_33; }
|
||||||
#define MCP2517_SDO 39 // SDO output of MCP2517
|
virtual gpio_num_t PRECHARGE_PIN() { return GPIO_NUM_25; }
|
||||||
#define MCP2517_CS 21 // CS input of MCP2517 //21 or 22
|
virtual gpio_num_t BMS_POWER() { return GPIO_NUM_2; }
|
||||||
#define MCP2517_INT 34 // INT output of MCP2517 //34 or 35
|
virtual gpio_num_t SECOND_BATTERY_CONTACTORS_PIN() { return GPIO_NUM_13; }
|
||||||
|
|
||||||
// CHAdeMO support pin dependencies
|
// Automatic precharging
|
||||||
#define CHADEMO_PIN_2 12
|
virtual gpio_num_t HIA4V1_PIN() { return GPIO_NUM_25; }
|
||||||
#define CHADEMO_PIN_10 5
|
virtual gpio_num_t INVERTER_DISCONNECT_CONTACTOR_PIN() { return GPIO_NUM_32; }
|
||||||
#define CHADEMO_PIN_7 34
|
|
||||||
#define CHADEMO_PIN_4 35
|
|
||||||
#define CHADEMO_LOCK 18
|
|
||||||
|
|
||||||
// Contactor handling
|
// SMA CAN contactor pins
|
||||||
#define POSITIVE_CONTACTOR_PIN 32
|
virtual gpio_num_t INVERTER_CONTACTOR_ENABLE_PIN() { return GPIO_NUM_36; }
|
||||||
#define NEGATIVE_CONTACTOR_PIN 33
|
virtual gpio_num_t INVERTER_CONTACTOR_ENABLE_LED_PIN() { return GPIO_NUM_NC; }
|
||||||
#define PRECHARGE_PIN 25
|
|
||||||
#define BMS_POWER 2
|
|
||||||
#define SECOND_BATTERY_CONTACTORS_PIN 13
|
|
||||||
|
|
||||||
// SMA CAN contactor pins
|
// SD card
|
||||||
#define INVERTER_CONTACTOR_ENABLE_PIN 36
|
virtual gpio_num_t SD_MISO_PIN() { return GPIO_NUM_2; }
|
||||||
|
virtual gpio_num_t SD_MOSI_PIN() { return GPIO_NUM_15; }
|
||||||
|
virtual gpio_num_t SD_SCLK_PIN() { return GPIO_NUM_14; }
|
||||||
|
virtual gpio_num_t SD_CS_PIN() { return GPIO_NUM_13; }
|
||||||
|
|
||||||
// Automatic precharging
|
// LED
|
||||||
#define HIA4V1_PIN 25
|
virtual gpio_num_t LED_PIN() { return GPIO_NUM_4; }
|
||||||
#define INVERTER_DISCONNECT_CONTACTOR_PIN 32
|
virtual uint8_t LED_MAX_BRIGHTNESS() { return 40; }
|
||||||
|
|
||||||
// SD card
|
// Equipment stop pin
|
||||||
//#define SD_MISO_PIN 2
|
virtual gpio_num_t EQUIPMENT_STOP_PIN() { return GPIO_NUM_35; }
|
||||||
//#define SD_MOSI_PIN 15
|
|
||||||
//#define SD_SCLK_PIN 14
|
|
||||||
//#define SD_CS_PIN 13
|
|
||||||
|
|
||||||
// LED
|
// Battery wake up pins
|
||||||
#define LED_PIN 4
|
virtual gpio_num_t WUP_PIN1() { return GPIO_NUM_25; }
|
||||||
#define LED_MAX_BRIGHTNESS 40
|
virtual gpio_num_t WUP_PIN2() { return GPIO_NUM_32; }
|
||||||
|
|
||||||
// Equipment stop pin
|
std::vector<comm_interface> available_interfaces() {
|
||||||
#define EQUIPMENT_STOP_PIN 35
|
return {comm_interface::Modbus, comm_interface::RS485, comm_interface::CanNative};
|
||||||
|
}
|
||||||
// BMW_I3_BATTERY wake up pin
|
};
|
||||||
#define WUP_PIN1 GPIO_NUM_25 // Wake up pin for battery 1
|
|
||||||
#define WUP_PIN2 GPIO_NUM_32 // Wake up pin for battery 2
|
|
||||||
|
|
||||||
/* ----- Error checks below, don't change (can't be moved to separate file) ----- */
|
|
||||||
#ifndef HW_CONFIGURED
|
|
||||||
#define HW_CONFIGURED
|
|
||||||
#else
|
|
||||||
#error Multiple HW defined! Please select a single HW
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef CHADEMO_BATTERY
|
|
||||||
#ifdef CAN_ADDON
|
|
||||||
#error CHADEMO and CAN_ADDON cannot coexist due to overlapping GPIO pin usage
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef EQUIPMENT_STOP_BUTTON
|
|
||||||
#ifdef CAN_ADDON
|
|
||||||
#error EQUIPMENT_STOP_BUTTON and CAN_ADDON cannot coexist due to overlapping GPIO pin usage
|
|
||||||
#endif
|
|
||||||
#ifdef CANFD_ADDON
|
|
||||||
#error EQUIPMENT_STOP_BUTTON and CANFD_ADDON cannot coexist due to overlapping GPIO pin usage
|
|
||||||
#endif
|
|
||||||
#ifdef CHADEMO_BATTERY
|
|
||||||
#error EQUIPMENT_STOP_BUTTON and CHADEMO_BATTERY cannot coexist due to overlapping GPIO pin usage
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef BMW_I3_BATTERY
|
|
||||||
#if defined(CONTACTOR_CONTROL) && defined(WUP_PIN1)
|
|
||||||
#error GPIO PIN 25 cannot be used for both BMWi3 Wakeup and contactor control. Disable CONTACTOR_CONTROL
|
|
||||||
#endif
|
|
||||||
#if defined(CONTACTOR_CONTROL) && defined(WUP_PIN2)
|
|
||||||
#error GPIO PIN 32 cannot be used for both BMWi3 Wakeup and contactor control. Disable CONTACTOR_CONTROL
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -11,83 +11,68 @@ The pin layout below supports the following:
|
||||||
- 1x CANFD (via MCP2518FD (SPI))
|
- 1x CANFD (via MCP2518FD (SPI))
|
||||||
*/
|
*/
|
||||||
|
|
||||||
// Board boot-up time
|
class DevKitHal : public Esp32Hal {
|
||||||
#define BOOTUP_TIME 1000 // Time in ms it takes before system is considered fully started up
|
public:
|
||||||
|
const char* name() { return "ESP32 DevKit V1"; }
|
||||||
|
|
||||||
// Core assignment
|
virtual gpio_num_t RS485_TX_PIN() { return GPIO_NUM_1; }
|
||||||
#define CORE_FUNCTION_CORE 1
|
virtual gpio_num_t RS485_RX_PIN() { return GPIO_NUM_3; }
|
||||||
#define MODBUS_CORE 0
|
|
||||||
#define WIFI_CORE 0
|
|
||||||
|
|
||||||
// RS485
|
virtual gpio_num_t CAN_TX_PIN() { return GPIO_NUM_27; }
|
||||||
#define RS485_TX_PIN GPIO_NUM_1
|
virtual gpio_num_t CAN_RX_PIN() { return GPIO_NUM_26; }
|
||||||
#define RS485_RX_PIN GPIO_NUM_3
|
|
||||||
|
|
||||||
// CAN settings
|
// CAN_ADDON
|
||||||
#define CAN_1_TYPE ESP32CAN
|
// SCK input of MCP2515
|
||||||
//#define CAN_2_TYPE MCP2515
|
virtual gpio_num_t MCP2515_SCK() { return GPIO_NUM_22; }
|
||||||
//#define CAN_3_TYPE MCP2518FD
|
// SDI input of MCP2515
|
||||||
|
virtual gpio_num_t MCP2515_MOSI() { return GPIO_NUM_21; }
|
||||||
|
// SDO output of MCP2515
|
||||||
|
virtual gpio_num_t MCP2515_MISO() { return GPIO_NUM_19; }
|
||||||
|
// CS input of MCP2515
|
||||||
|
virtual gpio_num_t MCP2515_CS() { return GPIO_NUM_18; }
|
||||||
|
// INT output of MCP2515
|
||||||
|
virtual gpio_num_t MCP2515_INT() { return GPIO_NUM_23; }
|
||||||
|
|
||||||
// CAN1 PIN mappings, do not change these unless you are adding on extra hardware to the PCB
|
// CANFD_ADDON defines for MCP2517
|
||||||
#define CAN_TX_PIN GPIO_NUM_27
|
virtual gpio_num_t MCP2517_SCK() { return GPIO_NUM_33; }
|
||||||
#define CAN_RX_PIN GPIO_NUM_26
|
virtual gpio_num_t MCP2517_SDI() { return GPIO_NUM_32; }
|
||||||
|
virtual gpio_num_t MCP2517_SDO() { return GPIO_NUM_35; }
|
||||||
|
virtual gpio_num_t MCP2517_CS() { return GPIO_NUM_25; }
|
||||||
|
virtual gpio_num_t MCP2517_INT() { return GPIO_NUM_34; }
|
||||||
|
|
||||||
// CAN_ADDON defines
|
// Contactor handling
|
||||||
#define MCP2515_SCK GPIO_NUM_22 // SCK input of MCP2515
|
virtual gpio_num_t POSITIVE_CONTACTOR_PIN() { return GPIO_NUM_5; }
|
||||||
#define MCP2515_MOSI GPIO_NUM_21 // SDI input of MCP2515
|
virtual gpio_num_t NEGATIVE_CONTACTOR_PIN() { return GPIO_NUM_16; }
|
||||||
#define MCP2515_MISO GPIO_NUM_19 // SDO output of MCP2515
|
virtual gpio_num_t PRECHARGE_PIN() { return GPIO_NUM_17; }
|
||||||
#define MCP2515_CS GPIO_NUM_18 // CS input of MCP2515
|
virtual gpio_num_t SECOND_BATTERY_CONTACTORS_PIN() { return GPIO_NUM_32; }
|
||||||
#define MCP2515_INT GPIO_NUM_23 // INT output of MCP2515
|
|
||||||
|
|
||||||
// CANFD_ADDON defines
|
// Automatic precharging
|
||||||
#define MCP2517_SCK GPIO_NUM_33 // SCK input of MCP2517
|
virtual gpio_num_t HIA4V1_PIN() { return GPIO_NUM_4; }
|
||||||
#define MCP2517_SDI GPIO_NUM_32 // SDI input of MCP2517
|
virtual gpio_num_t INVERTER_DISCONNECT_CONTACTOR_PIN() { return GPIO_NUM_5; }
|
||||||
#define MCP2517_SDO GPIO_NUM_35 // SDO output of MCP2517 | Pin 35 is input only, without pullup/down resistors
|
|
||||||
#define MCP2517_CS GPIO_NUM_25 // CS input of MCP2517
|
|
||||||
#define MCP2517_INT GPIO_NUM_34 // INT output of MCP2517 | Pin 34 is input only, without pullup/down resistors
|
|
||||||
|
|
||||||
// Contactor handling
|
// SMA CAN contactor pins
|
||||||
#define POSITIVE_CONTACTOR_PIN GPIO_NUM_5
|
virtual gpio_num_t INVERTER_CONTACTOR_ENABLE_PIN() { return GPIO_NUM_14; }
|
||||||
#define NEGATIVE_CONTACTOR_PIN GPIO_NUM_16
|
|
||||||
#define PRECHARGE_PIN GPIO_NUM_17
|
|
||||||
#define SECOND_BATTERY_CONTACTORS_PIN GPIO_NUM_32
|
|
||||||
// SMA CAN contactor pins
|
|
||||||
#define INVERTER_CONTACTOR_ENABLE_PIN GPIO_NUM_14
|
|
||||||
|
|
||||||
// LED
|
virtual gpio_num_t INVERTER_CONTACTOR_ENABLE_LED_PIN() { return GPIO_NUM_2; }
|
||||||
#define LED_PIN GPIO_NUM_4
|
|
||||||
#define LED_MAX_BRIGHTNESS 40
|
|
||||||
#define INVERTER_CONTACTOR_ENABLE_LED_PIN GPIO_NUM_2
|
|
||||||
|
|
||||||
// Equipment stop pin
|
// LED
|
||||||
#define EQUIPMENT_STOP_PIN GPIO_NUM_12
|
virtual gpio_num_t LED_PIN() { return GPIO_NUM_4; }
|
||||||
|
virtual uint8_t LED_MAX_BRIGHTNESS() { return 40; }
|
||||||
|
|
||||||
// Automatic precharging
|
// Equipment stop pin
|
||||||
#define HIA4V1_PIN GPIO_NUM_17
|
virtual gpio_num_t EQUIPMENT_STOP_PIN() { return GPIO_NUM_12; }
|
||||||
#define INVERTER_DISCONNECT_CONTACTOR_PIN GPIO_NUM_5
|
|
||||||
|
|
||||||
// BMW_I3_BATTERY wake up pin
|
// Battery wake up pins
|
||||||
#define WUP_PIN1 GPIO_NUM_25 // Wake up pin for battery 1
|
virtual gpio_num_t WUP_PIN1() { return GPIO_NUM_25; }
|
||||||
#define WUP_PIN2 GPIO_NUM_32 // Wake up pin for battery 2
|
virtual gpio_num_t WUP_PIN2() { return GPIO_NUM_32; }
|
||||||
|
|
||||||
/* ----- Error checks below, don't change (can't be moved to separate file) ----- */
|
std::vector<comm_interface> available_interfaces() {
|
||||||
#ifndef HW_CONFIGURED
|
return {
|
||||||
#define HW_CONFIGURED
|
comm_interface::Modbus,
|
||||||
#else
|
comm_interface::RS485,
|
||||||
#error Multiple HW defined! Please select a single HW
|
comm_interface::CanNative,
|
||||||
#endif // HW_CONFIGURED
|
};
|
||||||
|
}
|
||||||
#ifdef CHADEMO_BATTERY
|
};
|
||||||
#error CHADEMO pins are not defined for this hardware.
|
|
||||||
#endif // CHADEMO_BATTERY
|
|
||||||
|
|
||||||
#ifdef BMW_I3_BATTERY
|
|
||||||
#if defined(WUP_PIN1) && defined(CANFD_ADDON)
|
|
||||||
#error GPIO PIN 25 cannot be used for both BMWi3 Wakeup and a CANFD addon board using these pins. Choose between BMW_I3_BATTERY and CANFD_ADDON
|
|
||||||
#endif // defined(WUP_PIN1) && defined(CANFD_ADDON)
|
|
||||||
#if defined(WUP_PIN2) && defined(CANFD_ADDON)
|
|
||||||
#error GPIO PIN 32 cannot be used for both BMWi3 Wakeup and a CANFD addon board using these pins. Choose between BMW_I3_BATTERY and CANFD_ADDON
|
|
||||||
#endif // defined(WUP_PIN2) && defined(CANFD_ADDON)
|
|
||||||
#endif // BMW_I3_BATTERY
|
|
||||||
|
|
||||||
#endif // __HW_DEVKIT_H__
|
#endif // __HW_DEVKIT_H__
|
||||||
|
|
|
@ -1,82 +1,87 @@
|
||||||
#ifndef __HW_LILYGO_H__
|
#ifndef __HW_LILYGO_H__
|
||||||
#define __HW_LILYGO_H__
|
#define __HW_LILYGO_H__
|
||||||
|
|
||||||
// Board boot-up time
|
#include "hal.h"
|
||||||
#define BOOTUP_TIME 1000 // Time in ms it takes before system is considered fully started up
|
|
||||||
|
|
||||||
// Core assignment
|
class LilyGoHal : public Esp32Hal {
|
||||||
#define CORE_FUNCTION_CORE 1
|
public:
|
||||||
#define MODBUS_CORE 0
|
const char* name() { return "LilyGo T-CAN485"; }
|
||||||
#define WIFI_CORE 0
|
|
||||||
|
|
||||||
// RS485
|
virtual gpio_num_t PIN_5V_EN() { return GPIO_NUM_16; }
|
||||||
#define PIN_5V_EN 16
|
virtual gpio_num_t RS485_EN_PIN() { return GPIO_NUM_17; }
|
||||||
#define RS485_EN_PIN 17 // 17 /RE
|
virtual gpio_num_t RS485_TX_PIN() { return GPIO_NUM_22; }
|
||||||
#define RS485_TX_PIN 22 // 21
|
virtual gpio_num_t RS485_RX_PIN() { return GPIO_NUM_21; }
|
||||||
#define RS485_RX_PIN 21 // 22
|
virtual gpio_num_t RS485_SE_PIN() { return GPIO_NUM_19; }
|
||||||
#define RS485_SE_PIN 19 // 22 /SHDN
|
|
||||||
|
|
||||||
// CAN settings. CAN_2 is not defined as it can be either MCP2515 or MCP2517, defined by the user settings
|
virtual gpio_num_t CAN_TX_PIN() { return GPIO_NUM_27; }
|
||||||
#define CAN_1_TYPE ESP32CAN
|
virtual gpio_num_t CAN_RX_PIN() { return GPIO_NUM_26; }
|
||||||
|
virtual gpio_num_t CAN_SE_PIN() { return GPIO_NUM_23; }
|
||||||
|
|
||||||
// CAN1 PIN mappings, do not change these unless you are adding on extra hardware to the PCB
|
// CAN_ADDON
|
||||||
#define CAN_TX_PIN GPIO_NUM_27
|
// SCK input of MCP2515
|
||||||
#define CAN_RX_PIN GPIO_NUM_26
|
virtual gpio_num_t MCP2515_SCK() { return GPIO_NUM_12; }
|
||||||
#define CAN_SE_PIN 23
|
// SDI input of MCP2515
|
||||||
|
virtual gpio_num_t MCP2515_MOSI() { return GPIO_NUM_5; }
|
||||||
|
// SDO output of MCP2515
|
||||||
|
virtual gpio_num_t MCP2515_MISO() { return GPIO_NUM_34; }
|
||||||
|
// CS input of MCP2515
|
||||||
|
virtual gpio_num_t MCP2515_CS() { return GPIO_NUM_18; }
|
||||||
|
// INT output of MCP2515
|
||||||
|
virtual gpio_num_t MCP2515_INT() { return GPIO_NUM_35; }
|
||||||
|
|
||||||
// CAN2 defines below
|
// CANFD_ADDON defines for MCP2517
|
||||||
|
virtual gpio_num_t MCP2517_SCK() { return GPIO_NUM_12; }
|
||||||
|
virtual gpio_num_t MCP2517_SDI() { return GPIO_NUM_5; }
|
||||||
|
virtual gpio_num_t MCP2517_SDO() { return GPIO_NUM_34; }
|
||||||
|
virtual gpio_num_t MCP2517_CS() { return GPIO_NUM_18; }
|
||||||
|
virtual gpio_num_t MCP2517_INT() { return GPIO_NUM_35; }
|
||||||
|
|
||||||
// CAN_ADDON defines
|
// CHAdeMO support pin dependencies
|
||||||
#define MCP2515_SCK 12 // SCK input of MCP2515
|
virtual gpio_num_t CHADEMO_PIN_2() { return GPIO_NUM_12; }
|
||||||
#define MCP2515_MOSI 5 // SDI input of MCP2515
|
virtual gpio_num_t CHADEMO_PIN_10() { return GPIO_NUM_5; }
|
||||||
#define MCP2515_MISO 34 // SDO output of MCP2515 | Pin 34 is input only, without pullup/down resistors
|
virtual gpio_num_t CHADEMO_PIN_7() { return GPIO_NUM_34; }
|
||||||
#define MCP2515_CS 18 // CS input of MCP2515
|
virtual gpio_num_t CHADEMO_PIN_4() { return GPIO_NUM_35; }
|
||||||
#define MCP2515_INT 35 // INT output of MCP2515 | | Pin 35 is input only, without pullup/down resistors
|
virtual gpio_num_t CHADEMO_LOCK() { return GPIO_NUM_18; }
|
||||||
|
|
||||||
// CANFD_ADDON defines
|
// Contactor handling
|
||||||
#define MCP2517_SCK 12 // SCK input of MCP2517
|
virtual gpio_num_t POSITIVE_CONTACTOR_PIN() { return GPIO_NUM_32; }
|
||||||
#define MCP2517_SDI 5 // SDI input of MCP2517
|
virtual gpio_num_t NEGATIVE_CONTACTOR_PIN() { return GPIO_NUM_33; }
|
||||||
#define MCP2517_SDO 34 // SDO output of MCP2517
|
virtual gpio_num_t PRECHARGE_PIN() { return GPIO_NUM_25; }
|
||||||
#define MCP2517_CS 18 // CS input of MCP2517
|
virtual gpio_num_t BMS_POWER() { return GPIO_NUM_18; }
|
||||||
#define MCP2517_INT 35 // INT output of MCP2517
|
virtual gpio_num_t SECOND_BATTERY_CONTACTORS_PIN() { return GPIO_NUM_15; }
|
||||||
|
|
||||||
// CHAdeMO support pin dependencies
|
// Automatic precharging
|
||||||
#define CHADEMO_PIN_2 12
|
virtual gpio_num_t HIA4V1_PIN() { return GPIO_NUM_25; }
|
||||||
#define CHADEMO_PIN_10 5
|
virtual gpio_num_t INVERTER_DISCONNECT_CONTACTOR_PIN() { return GPIO_NUM_32; }
|
||||||
#define CHADEMO_PIN_7 34
|
|
||||||
#define CHADEMO_PIN_4 35
|
|
||||||
#define CHADEMO_LOCK 18
|
|
||||||
|
|
||||||
// Contactor handling
|
// SMA CAN contactor pins
|
||||||
#define POSITIVE_CONTACTOR_PIN 32
|
virtual gpio_num_t INVERTER_CONTACTOR_ENABLE_PIN() { return GPIO_NUM_5; }
|
||||||
#define NEGATIVE_CONTACTOR_PIN 33
|
|
||||||
#define PRECHARGE_PIN 25
|
|
||||||
#define BMS_POWER 18 // Note, this pin collides with CAN add-ons and Chademo
|
|
||||||
#define SECOND_BATTERY_CONTACTORS_PIN 15 //Note, this pin collides with SD card pins
|
|
||||||
|
|
||||||
// Automatic precharging
|
// virtual gpio_num_t INVERTER_CONTACTOR_ENABLE_LED_PIN() { return GPIO_NUM_NC; }
|
||||||
#define HIA4V1_PIN 25
|
|
||||||
#define INVERTER_DISCONNECT_CONTACTOR_PIN 32
|
|
||||||
|
|
||||||
// SMA CAN contactor pins
|
// SD card
|
||||||
#define INVERTER_CONTACTOR_ENABLE_PIN 5
|
virtual gpio_num_t SD_MISO_PIN() { return GPIO_NUM_2; }
|
||||||
|
virtual gpio_num_t SD_MOSI_PIN() { return GPIO_NUM_15; }
|
||||||
|
virtual gpio_num_t SD_SCLK_PIN() { return GPIO_NUM_14; }
|
||||||
|
virtual gpio_num_t SD_CS_PIN() { return GPIO_NUM_13; }
|
||||||
|
|
||||||
// SD card
|
// LED
|
||||||
#define SD_MISO_PIN 2
|
virtual gpio_num_t LED_PIN() { return GPIO_NUM_4; }
|
||||||
#define SD_MOSI_PIN 15
|
|
||||||
#define SD_SCLK_PIN 14
|
|
||||||
#define SD_CS_PIN 13
|
|
||||||
|
|
||||||
// LED
|
// Equipment stop pin
|
||||||
#define LED_PIN 4
|
virtual gpio_num_t EQUIPMENT_STOP_PIN() { return GPIO_NUM_35; }
|
||||||
#define LED_MAX_BRIGHTNESS 40
|
|
||||||
|
|
||||||
// Equipment stop pin
|
// Battery wake up pins
|
||||||
#define EQUIPMENT_STOP_PIN 35
|
virtual gpio_num_t WUP_PIN1() { return GPIO_NUM_25; }
|
||||||
|
virtual gpio_num_t WUP_PIN2() { return GPIO_NUM_32; }
|
||||||
|
|
||||||
// BMW_I3_BATTERY wake up pin
|
std::vector<comm_interface> available_interfaces() {
|
||||||
#define WUP_PIN1 GPIO_NUM_25 // Wake up pin for battery 1
|
return {comm_interface::Modbus, comm_interface::RS485, comm_interface::CanNative, comm_interface::CanAddonMcp2515,
|
||||||
#define WUP_PIN2 GPIO_NUM_32 // Wake up pin for battery 2
|
comm_interface::CanFdAddonMcp2518};
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
#define HalClass LilyGoHal
|
||||||
|
|
||||||
/* ----- Error checks below, don't change (can't be moved to separate file) ----- */
|
/* ----- Error checks below, don't change (can't be moved to separate file) ----- */
|
||||||
#ifndef HW_CONFIGURED
|
#ifndef HW_CONFIGURED
|
||||||
|
@ -85,42 +90,4 @@
|
||||||
#error Multiple HW defined! Please select a single HW
|
#error Multiple HW defined! Please select a single HW
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(CAN_ADDON) && defined(CANFD_ADDON)
|
|
||||||
// Check that user did not try to use dual can and fd-can on same hardware pins
|
|
||||||
#error CAN_ADDON AND CANFD_ADDON CANNOT BE USED SIMULTANEOUSLY
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if defined(SMA_BYD_H_CAN) || defined(SMA_BYD_HVS_CAN) || defined(SMA_TRIPOWER_CAN)
|
|
||||||
#if defined(CAN_ADDON) || defined(CANFD_ADDON)
|
|
||||||
#error Pin 5 used by both Enable line and for CAN-ADDON. Please reconfigure this, and remove this line to proceed
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef CHADEMO_BATTERY
|
|
||||||
#ifdef CAN_ADDON
|
|
||||||
#error CHADEMO and CAN_ADDON cannot coexist due to overlapping GPIO pin usage
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef EQUIPMENT_STOP_BUTTON
|
|
||||||
#ifdef CAN_ADDON
|
|
||||||
#error EQUIPMENT_STOP_BUTTON and CAN_ADDON cannot coexist due to overlapping GPIO pin usage
|
|
||||||
#endif
|
|
||||||
#ifdef CANFD_ADDON
|
|
||||||
#error EQUIPMENT_STOP_BUTTON and CANFD_ADDON cannot coexist due to overlapping GPIO pin usage
|
|
||||||
#endif
|
|
||||||
#ifdef CHADEMO_BATTERY
|
|
||||||
#error EQUIPMENT_STOP_BUTTON and CHADEMO_BATTERY cannot coexist due to overlapping GPIO pin usage
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef BMW_I3_BATTERY
|
|
||||||
#if defined(CONTACTOR_CONTROL) && defined(WUP_PIN1)
|
|
||||||
#error GPIO PIN 25 cannot be used for both BMWi3 Wakeup and contactor control. Disable CONTACTOR_CONTROL
|
|
||||||
#endif
|
|
||||||
#if defined(CONTACTOR_CONTROL) && defined(WUP_PIN2)
|
|
||||||
#error GPIO PIN 32 cannot be used for both BMWi3 Wakeup and contactor control. Disable CONTACTOR_CONTROL
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -1,6 +1,8 @@
|
||||||
#ifndef __HW_STARK_H__
|
#ifndef __HW_STARK_H__
|
||||||
#define __HW_STARK_H__
|
#define __HW_STARK_H__
|
||||||
|
|
||||||
|
#include "hal.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
Stark CMR v1 - DIN-rail module with 4 power outputs, 1 x rs485, 1 x can and 1 x can-fd channel.
|
Stark CMR v1 - DIN-rail module with 4 power outputs, 1 x rs485, 1 x can and 1 x can-fd channel.
|
||||||
For more information on this board visit the project discord or contact johan@redispose.se
|
For more information on this board visit the project discord or contact johan@redispose.se
|
||||||
|
@ -15,75 +17,61 @@ GPIOs on extra header
|
||||||
* GPIO 15 (JTAG TDO)
|
* GPIO 15 (JTAG TDO)
|
||||||
*/
|
*/
|
||||||
|
|
||||||
// Board boot-up time
|
class StarkHal : public Esp32Hal {
|
||||||
#define BOOTUP_TIME 5000 // Time in ms it takes before system is considered fully started up
|
public:
|
||||||
|
const char* name() { return "Stark CMR Module"; }
|
||||||
|
|
||||||
// Core assignment
|
// Not needed, GPIO 16 has hardware pullup for PSRAM compatibility
|
||||||
#define CORE_FUNCTION_CORE 1
|
virtual gpio_num_t PIN_5V_EN() { return GPIO_NUM_NC; }
|
||||||
#define MODBUS_CORE 0
|
|
||||||
#define WIFI_CORE 0
|
|
||||||
|
|
||||||
// RS485
|
// Not needed, GPIO 17 is used as SCK input of MCP2517
|
||||||
// #define PIN_5V_EN 16 // Not needed, GPIO 16 has hardware pullup for PSRAM compatibility
|
virtual gpio_num_t RS485_EN_PIN() { return GPIO_NUM_NC; }
|
||||||
// #define RS485_EN_PIN 17 // Not needed, GPIO 17 is used as SCK input of MCP2517
|
virtual gpio_num_t RS485_TX_PIN() { return GPIO_NUM_22; }
|
||||||
#define RS485_TX_PIN 22
|
virtual gpio_num_t RS485_RX_PIN() { return GPIO_NUM_21; }
|
||||||
#define RS485_RX_PIN 21
|
// Not needed, GPIO 19 is available as extra GPIO via pin header
|
||||||
// #define RS485_SE_PIN 19 // Not needed, GPIO 19 is available as extra GPIO via pin header
|
virtual gpio_num_t RS485_SE_PIN() { return GPIO_NUM_NC; }
|
||||||
|
|
||||||
// CAN settings
|
virtual gpio_num_t CAN_TX_PIN() { return GPIO_NUM_27; }
|
||||||
#define CAN_1_TYPE ESP32CAN
|
virtual gpio_num_t CAN_RX_PIN() { return GPIO_NUM_26; }
|
||||||
|
|
||||||
// CAN1 PIN mappings, do not change these unless you are adding on extra hardware to the PCB
|
// (No function, GPIO 23 used instead as MCP_SCK)
|
||||||
#define CAN_TX_PIN GPIO_NUM_27
|
virtual gpio_num_t CAN_SE_PIN() { return GPIO_NUM_NC; }
|
||||||
#define CAN_RX_PIN GPIO_NUM_26
|
|
||||||
// #define CAN_SE_PIN 23 // (No function, GPIO 23 used instead as MCP_SCK)
|
|
||||||
|
|
||||||
// CANFD_ADDON defines
|
// CANFD_ADDON defines for MCP2517
|
||||||
#define MCP2517_SCK 17 // SCK input of MCP2517
|
virtual gpio_num_t MCP2517_SCK() { return GPIO_NUM_17; }
|
||||||
#define MCP2517_SDI 5 // SDI input of MCP2517
|
virtual gpio_num_t MCP2517_SDI() { return GPIO_NUM_5; }
|
||||||
#define MCP2517_SDO 34 // SDO output of MCP2517
|
virtual gpio_num_t MCP2517_SDO() { return GPIO_NUM_34; }
|
||||||
#define MCP2517_CS 18 // CS input of MCP2517
|
virtual gpio_num_t MCP2517_CS() { return GPIO_NUM_18; }
|
||||||
#define MCP2517_INT 35 // INT output of MCP2517
|
virtual gpio_num_t MCP2517_INT() { return GPIO_NUM_35; }
|
||||||
|
|
||||||
// Contactor handling
|
// Contactor handling
|
||||||
#define POSITIVE_CONTACTOR_PIN 32
|
virtual gpio_num_t POSITIVE_CONTACTOR_PIN() { return GPIO_NUM_32; }
|
||||||
#define NEGATIVE_CONTACTOR_PIN 33
|
virtual gpio_num_t NEGATIVE_CONTACTOR_PIN() { return GPIO_NUM_33; }
|
||||||
#define PRECHARGE_PIN 25
|
virtual gpio_num_t PRECHARGE_PIN() { return GPIO_NUM_25; }
|
||||||
#define BMS_POWER 23
|
virtual gpio_num_t BMS_POWER() { return GPIO_NUM_23; }
|
||||||
#define SECOND_BATTERY_CONTACTORS_PIN 19 //Available as extra GPIO via pin header
|
virtual gpio_num_t SECOND_BATTERY_CONTACTORS_PIN() { return GPIO_NUM_19; }
|
||||||
|
|
||||||
// Automatic precharging
|
// Automatic precharging
|
||||||
#define HIA4V1_PIN 19 //Available as extra GPIO via pin header
|
virtual gpio_num_t HIA4V1_PIN() { return GPIO_NUM_19; }
|
||||||
#define INVERTER_DISCONNECT_CONTACTOR_PIN 25
|
virtual gpio_num_t INVERTER_DISCONNECT_CONTACTOR_PIN() { return GPIO_NUM_25; }
|
||||||
|
|
||||||
// SMA CAN contactor pins
|
// SMA CAN contactor pins
|
||||||
#define INVERTER_CONTACTOR_ENABLE_PIN 2
|
virtual gpio_num_t INVERTER_CONTACTOR_ENABLE_PIN() { return GPIO_NUM_2; }
|
||||||
|
|
||||||
// LED
|
// LED
|
||||||
#define LED_PIN 4
|
virtual gpio_num_t LED_PIN() { return GPIO_NUM_4; }
|
||||||
#define LED_MAX_BRIGHTNESS 40
|
virtual uint8_t LED_MAX_BRIGHTNESS() { return 40; }
|
||||||
|
|
||||||
// Equipment stop pin
|
// Equipment stop pin
|
||||||
#define EQUIPMENT_STOP_PIN 2
|
virtual gpio_num_t EQUIPMENT_STOP_PIN() { return GPIO_NUM_2; }
|
||||||
|
|
||||||
// BMW_I3_BATTERY wake up pin
|
// Battery wake up pins
|
||||||
#define WUP_PIN1 GPIO_NUM_25 // Wake up pin for battery 1
|
virtual gpio_num_t WUP_PIN1() { return GPIO_NUM_25; }
|
||||||
#define WUP_PIN2 GPIO_NUM_32 // Wake up pin for battery 2
|
virtual gpio_num_t WUP_PIN2() { return GPIO_NUM_32; }
|
||||||
|
|
||||||
/* ----- Error checks below, don't change (can't be moved to separate file) ----- */
|
std::vector<comm_interface> available_interfaces() {
|
||||||
#ifndef HW_CONFIGURED
|
return {comm_interface::Modbus, comm_interface::RS485, comm_interface::CanNative, comm_interface::CanFdNative};
|
||||||
#define HW_CONFIGURED
|
}
|
||||||
#else
|
};
|
||||||
#error Multiple HW defined! Please select a single HW
|
|
||||||
#endif // HW_CONFIGURED
|
|
||||||
|
|
||||||
#ifdef BMW_I3_BATTERY
|
|
||||||
#if defined(CONTACTOR_CONTROL) && defined(WUP_PIN1)
|
|
||||||
#error GPIO PIN 25 cannot be used for both BMWi3 Wakeup and contactor control. Disable CONTACTOR_CONTROL
|
|
||||||
#endif
|
|
||||||
#if defined(CONTACTOR_CONTROL) && defined(WUP_PIN2)
|
|
||||||
#error GPIO PIN 32 cannot be used for both BMWi3 Wakeup and contactor control. Disable CONTACTOR_CONTROL
|
|
||||||
#endif
|
|
||||||
#endif // BMW_I3_BATTERY
|
|
||||||
|
|
||||||
#endif // __HW_STARK_H__
|
#endif // __HW_STARK_H__
|
||||||
|
|
|
@ -2,6 +2,7 @@
|
||||||
#include <Arduino.h>
|
#include <Arduino.h>
|
||||||
#include <WiFi.h>
|
#include <WiFi.h>
|
||||||
#include <freertos/FreeRTOS.h>
|
#include <freertos/FreeRTOS.h>
|
||||||
|
#include <src/communication/nvm/comm_nvm.h>
|
||||||
#include <list>
|
#include <list>
|
||||||
#include "../../../USER_SECRETS.h"
|
#include "../../../USER_SECRETS.h"
|
||||||
#include "../../../USER_SETTINGS.h"
|
#include "../../../USER_SETTINGS.h"
|
||||||
|
@ -13,6 +14,41 @@
|
||||||
#include "../utils/timer.h"
|
#include "../utils/timer.h"
|
||||||
#include "mqtt_client.h"
|
#include "mqtt_client.h"
|
||||||
|
|
||||||
|
#ifdef MQTT
|
||||||
|
const bool mqtt_enabled_default = true;
|
||||||
|
#else
|
||||||
|
const bool mqtt_enabled_default = false;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
bool mqtt_enabled = mqtt_enabled_default;
|
||||||
|
|
||||||
|
#ifdef HA_AUTODISCOVERY
|
||||||
|
const bool ha_autodiscovery_enabled_default = true;
|
||||||
|
#else
|
||||||
|
const bool ha_autodiscovery_enabled_default = false;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
bool ha_autodiscovery_enabled = ha_autodiscovery_enabled_default;
|
||||||
|
|
||||||
|
#ifdef COMMON_IMAGE
|
||||||
|
const int mqtt_port_default = 0;
|
||||||
|
const char* mqtt_server_default = "";
|
||||||
|
#else
|
||||||
|
const int mqtt_port_default = MQTT_PORT;
|
||||||
|
const char* mqtt_server_default = MQTT_SERVER;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
int mqtt_port = mqtt_port_default;
|
||||||
|
std::string mqtt_server = mqtt_server_default;
|
||||||
|
|
||||||
|
#ifdef MQTT_MANUAL_TOPIC_OBJECT_NAME
|
||||||
|
const bool mqtt_manual_topic_object_name_default = true;
|
||||||
|
#else
|
||||||
|
const bool mqtt_manual_topic_object_name_default = false;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
bool mqtt_manual_topic_object_name = mqtt_manual_topic_object_name_default;
|
||||||
|
|
||||||
esp_mqtt_client_config_t mqtt_cfg;
|
esp_mqtt_client_config_t mqtt_cfg;
|
||||||
esp_mqtt_client_handle_t client;
|
esp_mqtt_client_handle_t client;
|
||||||
char mqtt_msg[MQTT_MSG_BUFFER_SIZE];
|
char mqtt_msg[MQTT_MSG_BUFFER_SIZE];
|
||||||
|
@ -59,7 +95,6 @@ static void publish_values(void) {
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef HA_AUTODISCOVERY
|
|
||||||
static bool ha_common_info_published = false;
|
static bool ha_common_info_published = false;
|
||||||
static bool ha_cell_voltages_published = false;
|
static bool ha_cell_voltages_published = false;
|
||||||
static bool ha_events_published = false;
|
static bool ha_events_published = false;
|
||||||
|
@ -176,7 +211,6 @@ void set_battery_voltage_attributes(JsonDocument& doc, int i, int cellNumber, co
|
||||||
doc["unit_of_measurement"] = "V";
|
doc["unit_of_measurement"] = "V";
|
||||||
doc["value_template"] = "{{ value_json.cell_voltages[" + String(i) + "] }}";
|
doc["value_template"] = "{{ value_json.cell_voltages[" + String(i) + "] }}";
|
||||||
}
|
}
|
||||||
#endif // HA_AUTODISCOVERY
|
|
||||||
|
|
||||||
static String generateButtonTopic(const char* subtype) {
|
static String generateButtonTopic(const char* subtype) {
|
||||||
return topic_name + "/command/" + String(subtype);
|
return topic_name + "/command/" + String(subtype);
|
||||||
|
@ -230,8 +264,10 @@ static std::vector<EventData> order_events;
|
||||||
static bool publish_common_info(void) {
|
static bool publish_common_info(void) {
|
||||||
static JsonDocument doc;
|
static JsonDocument doc;
|
||||||
static String state_topic = topic_name + "/info";
|
static String state_topic = topic_name + "/info";
|
||||||
#ifdef HA_AUTODISCOVERY
|
|
||||||
if (ha_common_info_published == false) {
|
// if(ha_autodiscovery_enabled) {
|
||||||
|
|
||||||
|
if (ha_autodiscovery_enabled && !ha_common_info_published) {
|
||||||
for (auto& config : sensorConfigs) {
|
for (auto& config : sensorConfigs) {
|
||||||
if (!config.condition(battery)) {
|
if (!config.condition(battery)) {
|
||||||
continue;
|
continue;
|
||||||
|
@ -260,18 +296,17 @@ static bool publish_common_info(void) {
|
||||||
}
|
}
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
#endif // HA_AUTODISCOVERY
|
|
||||||
doc["bms_status"] = getBMSStatus(datalayer.battery.status.bms_status);
|
doc["bms_status"] = getBMSStatus(datalayer.battery.status.bms_status);
|
||||||
doc["pause_status"] = get_emulator_pause_status();
|
doc["pause_status"] = get_emulator_pause_status();
|
||||||
|
|
||||||
//only publish these values if BMS is active and we are comunication with the battery (can send CAN messages to the battery)
|
//only publish these values if BMS is active and we are comunication with the battery (can send CAN messages to the battery)
|
||||||
if (datalayer.battery.status.CAN_battery_still_alive && allowed_to_send_CAN && millis() > BOOTUP_TIME) {
|
if (datalayer.battery.status.CAN_battery_still_alive && allowed_to_send_CAN && esp32hal->system_booted_up()) {
|
||||||
set_battery_attributes(doc, datalayer.battery, "", battery->supports_charged_energy());
|
set_battery_attributes(doc, datalayer.battery, "", battery->supports_charged_energy());
|
||||||
}
|
}
|
||||||
|
|
||||||
if (battery2) {
|
if (battery2) {
|
||||||
//only publish these values if BMS is active and we are comunication with the battery (can send CAN messages to the battery)
|
//only publish these values if BMS is active and we are comunication with the battery (can send CAN messages to the battery)
|
||||||
if (datalayer.battery2.status.CAN_battery_still_alive && allowed_to_send_CAN && millis() > BOOTUP_TIME) {
|
if (datalayer.battery2.status.CAN_battery_still_alive && allowed_to_send_CAN && esp32hal->system_booted_up()) {
|
||||||
set_battery_attributes(doc, datalayer.battery2, "_2", battery2->supports_charged_energy());
|
set_battery_attributes(doc, datalayer.battery2, "_2", battery2->supports_charged_energy());
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -283,9 +318,7 @@ static bool publish_common_info(void) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
doc.clear();
|
doc.clear();
|
||||||
#ifdef HA_AUTODISCOVERY
|
|
||||||
}
|
}
|
||||||
#endif // HA_AUTODISCOVERY
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -294,7 +327,7 @@ static bool publish_cell_voltages(void) {
|
||||||
static String state_topic = topic_name + "/spec_data";
|
static String state_topic = topic_name + "/spec_data";
|
||||||
static String state_topic_2 = topic_name + "/spec_data_2";
|
static String state_topic_2 = topic_name + "/spec_data_2";
|
||||||
|
|
||||||
#ifdef HA_AUTODISCOVERY
|
if (ha_autodiscovery_enabled) {
|
||||||
bool failed_to_publish = false;
|
bool failed_to_publish = false;
|
||||||
if (ha_cell_voltages_published == false) {
|
if (ha_cell_voltages_published == false) {
|
||||||
|
|
||||||
|
@ -338,7 +371,7 @@ static bool publish_cell_voltages(void) {
|
||||||
if (failed_to_publish == false) {
|
if (failed_to_publish == false) {
|
||||||
ha_cell_voltages_published = true;
|
ha_cell_voltages_published = true;
|
||||||
}
|
}
|
||||||
#endif // HA_AUTODISCOVERY
|
}
|
||||||
|
|
||||||
// If cell voltages have been populated...
|
// If cell voltages have been populated...
|
||||||
if (datalayer.battery.info.number_of_cells != 0u &&
|
if (datalayer.battery.info.number_of_cells != 0u &&
|
||||||
|
@ -434,8 +467,7 @@ static bool publish_cell_balancing(void) {
|
||||||
bool publish_events() {
|
bool publish_events() {
|
||||||
static JsonDocument doc;
|
static JsonDocument doc;
|
||||||
static String state_topic = topic_name + "/events";
|
static String state_topic = topic_name + "/events";
|
||||||
#ifdef HA_AUTODISCOVERY
|
if (ha_autodiscovery_enabled && !ha_events_published) {
|
||||||
if (ha_events_published == false) {
|
|
||||||
|
|
||||||
doc["name"] = "Event";
|
doc["name"] = "Event";
|
||||||
doc["state_topic"] = state_topic;
|
doc["state_topic"] = state_topic;
|
||||||
|
@ -456,8 +488,6 @@ bool publish_events() {
|
||||||
|
|
||||||
doc.clear();
|
doc.clear();
|
||||||
} else {
|
} else {
|
||||||
#endif // HA_AUTODISCOVERY
|
|
||||||
|
|
||||||
const EVENTS_STRUCT_TYPE* event_pointer;
|
const EVENTS_STRUCT_TYPE* event_pointer;
|
||||||
|
|
||||||
//clear the vector
|
//clear the vector
|
||||||
|
@ -481,7 +511,7 @@ bool publish_events() {
|
||||||
doc["severity"] = String(get_event_level_string(event_handle));
|
doc["severity"] = String(get_event_level_string(event_handle));
|
||||||
doc["count"] = String(event_pointer->occurences);
|
doc["count"] = String(event_pointer->occurences);
|
||||||
doc["data"] = String(event_pointer->data);
|
doc["data"] = String(event_pointer->data);
|
||||||
doc["message"] = String(get_event_message_string(event_handle));
|
doc["message"] = get_event_message_string(event_handle);
|
||||||
doc["millis"] = String(event_pointer->timestamp);
|
doc["millis"] = String(event_pointer->timestamp);
|
||||||
|
|
||||||
serializeJson(doc, mqtt_msg);
|
serializeJson(doc, mqtt_msg);
|
||||||
|
@ -497,14 +527,12 @@ bool publish_events() {
|
||||||
//clear the vector
|
//clear the vector
|
||||||
order_events.clear();
|
order_events.clear();
|
||||||
}
|
}
|
||||||
#ifdef HA_AUTODISCOVERY
|
|
||||||
}
|
}
|
||||||
#endif // HA_AUTODISCOVERY
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
static bool publish_buttons_discovery(void) {
|
static bool publish_buttons_discovery(void) {
|
||||||
#ifdef HA_AUTODISCOVERY
|
if (ha_autodiscovery_enabled) {
|
||||||
if (ha_buttons_published == false) {
|
if (ha_buttons_published == false) {
|
||||||
#ifdef DEBUG_LOG
|
#ifdef DEBUG_LOG
|
||||||
logging.println("Publishing buttons discovery");
|
logging.println("Publishing buttons discovery");
|
||||||
|
@ -526,7 +554,7 @@ static bool publish_buttons_discovery(void) {
|
||||||
doc.clear();
|
doc.clear();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif // HA_AUTODISCOVERY
|
}
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -608,33 +636,59 @@ static void mqtt_event_handler(void* handler_args, esp_event_base_t base, int32_
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void init_mqtt(void) {
|
bool init_mqtt(void) {
|
||||||
#ifdef HA_AUTODISCOVERY
|
if (ha_autodiscovery_enabled) {
|
||||||
create_battery_sensor_configs();
|
create_battery_sensor_configs();
|
||||||
create_global_sensor_configs();
|
create_global_sensor_configs();
|
||||||
#endif // HA_AUTODISCOVERY
|
}
|
||||||
#ifdef MQTT_MANUAL_TOPIC_OBJECT_NAME
|
|
||||||
|
if (mqtt_manual_topic_object_name) {
|
||||||
|
#ifdef COMMON_IMAGE
|
||||||
|
BatteryEmulatorSettingsStore settings;
|
||||||
|
topic_name = settings.getString("MQTTTOPIC", mqtt_topic_name);
|
||||||
|
object_id_prefix = settings.getString("MQTTOBJIDPREFIX", mqtt_object_id_prefix);
|
||||||
|
device_name = settings.getString("MQTTDEVICENAME", mqtt_device_name);
|
||||||
|
device_id = settings.getString("HADEVICEID", ha_device_id);
|
||||||
|
|
||||||
|
if (topic_name.length() == 0) {
|
||||||
|
topic_name = mqtt_topic_name;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (object_id_prefix.length() == 0) {
|
||||||
|
object_id_prefix = mqtt_object_id_prefix;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (device_name.length() == 0) {
|
||||||
|
device_name = mqtt_device_name;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (device_id.length() == 0) {
|
||||||
|
device_id = ha_device_id;
|
||||||
|
}
|
||||||
|
|
||||||
|
#else
|
||||||
// Use custom topic name, object ID prefix, and device name from user settings
|
// Use custom topic name, object ID prefix, and device name from user settings
|
||||||
topic_name = mqtt_topic_name;
|
topic_name = mqtt_topic_name;
|
||||||
object_id_prefix = mqtt_object_id_prefix;
|
object_id_prefix = mqtt_object_id_prefix;
|
||||||
device_name = mqtt_device_name;
|
device_name = mqtt_device_name;
|
||||||
device_id = ha_device_id;
|
device_id = ha_device_id;
|
||||||
#else
|
#endif
|
||||||
|
} else {
|
||||||
// Use default naming based on WiFi hostname for topic, object ID prefix, and device name
|
// Use default naming based on WiFi hostname for topic, object ID prefix, and device name
|
||||||
topic_name = "battery-emulator_" + String(WiFi.getHostname());
|
topic_name = "battery-emulator_" + String(WiFi.getHostname());
|
||||||
object_id_prefix = String(WiFi.getHostname()) + String("_");
|
object_id_prefix = String(WiFi.getHostname()) + String("_");
|
||||||
device_name = "BatteryEmulator_" + String(WiFi.getHostname());
|
device_name = "BatteryEmulator_" + String(WiFi.getHostname());
|
||||||
device_id = "battery-emulator";
|
device_id = "battery-emulator";
|
||||||
#endif
|
}
|
||||||
|
|
||||||
String clientId = String("BatteryEmulatorClient-") + WiFi.getHostname();
|
String clientId = String("BatteryEmulatorClient-") + WiFi.getHostname();
|
||||||
|
|
||||||
mqtt_cfg.broker.address.transport = MQTT_TRANSPORT_OVER_TCP;
|
mqtt_cfg.broker.address.transport = MQTT_TRANSPORT_OVER_TCP;
|
||||||
mqtt_cfg.broker.address.hostname = MQTT_SERVER;
|
mqtt_cfg.broker.address.hostname = mqtt_server.c_str();
|
||||||
mqtt_cfg.broker.address.port = MQTT_PORT;
|
mqtt_cfg.broker.address.port = mqtt_port;
|
||||||
mqtt_cfg.credentials.client_id = clientId.c_str();
|
mqtt_cfg.credentials.client_id = clientId.c_str();
|
||||||
mqtt_cfg.credentials.username = MQTT_USER;
|
mqtt_cfg.credentials.username = mqtt_user.c_str();
|
||||||
mqtt_cfg.credentials.authentication.password = MQTT_PASSWORD;
|
mqtt_cfg.credentials.authentication.password = mqtt_password.c_str();
|
||||||
lwt_topic = topic_name + "/status";
|
lwt_topic = topic_name + "/status";
|
||||||
mqtt_cfg.session.last_will.topic = lwt_topic.c_str();
|
mqtt_cfg.session.last_will.topic = lwt_topic.c_str();
|
||||||
mqtt_cfg.session.last_will.qos = 1;
|
mqtt_cfg.session.last_will.qos = 1;
|
||||||
|
@ -643,7 +697,16 @@ void init_mqtt(void) {
|
||||||
mqtt_cfg.session.last_will.msg_len = strlen(mqtt_cfg.session.last_will.msg);
|
mqtt_cfg.session.last_will.msg_len = strlen(mqtt_cfg.session.last_will.msg);
|
||||||
mqtt_cfg.network.timeout_ms = MQTT_TIMEOUT;
|
mqtt_cfg.network.timeout_ms = MQTT_TIMEOUT;
|
||||||
client = esp_mqtt_client_init(&mqtt_cfg);
|
client = esp_mqtt_client_init(&mqtt_cfg);
|
||||||
esp_mqtt_client_register_event(client, MQTT_EVENT_ANY, mqtt_event_handler, client);
|
|
||||||
|
if (client == nullptr) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (esp_mqtt_client_register_event(client, MQTT_EVENT_ANY, mqtt_event_handler, client) != ESP_OK) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
void mqtt_loop(void) {
|
void mqtt_loop(void) {
|
||||||
|
|
|
@ -42,8 +42,10 @@
|
||||||
|
|
||||||
extern const char* version_number; // The current software version, used for mqtt
|
extern const char* version_number; // The current software version, used for mqtt
|
||||||
|
|
||||||
extern const char* mqtt_user;
|
extern std::string mqtt_server;
|
||||||
extern const char* mqtt_password;
|
extern std::string mqtt_user;
|
||||||
|
extern std::string mqtt_password;
|
||||||
|
extern int mqtt_port;
|
||||||
extern const char* mqtt_topic_name;
|
extern const char* mqtt_topic_name;
|
||||||
extern const char* mqtt_object_id_prefix;
|
extern const char* mqtt_object_id_prefix;
|
||||||
extern const char* mqtt_device_name;
|
extern const char* mqtt_device_name;
|
||||||
|
@ -51,8 +53,11 @@ extern const char* ha_device_id;
|
||||||
|
|
||||||
extern char mqtt_msg[MQTT_MSG_BUFFER_SIZE];
|
extern char mqtt_msg[MQTT_MSG_BUFFER_SIZE];
|
||||||
|
|
||||||
void init_mqtt(void);
|
bool init_mqtt(void);
|
||||||
void mqtt_loop(void);
|
void mqtt_loop(void);
|
||||||
bool mqtt_publish(const char* topic, const char* mqtt_msg, bool retain);
|
bool mqtt_publish(const char* topic, const char* mqtt_msg, bool retain);
|
||||||
|
|
||||||
|
extern bool mqtt_enabled;
|
||||||
|
extern bool ha_autodiscovery_enabled;
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -1,4 +1,6 @@
|
||||||
|
#include "safety.h"
|
||||||
#include "../../datalayer/datalayer.h"
|
#include "../../datalayer/datalayer.h"
|
||||||
|
#include "../../include.h"
|
||||||
#include "../utils/events.h"
|
#include "../utils/events.h"
|
||||||
|
|
||||||
static uint16_t cell_deviation_mV = 0;
|
static uint16_t cell_deviation_mV = 0;
|
||||||
|
@ -328,6 +330,7 @@ void update_machineryprotection() {
|
||||||
|
|
||||||
//battery pause status begin
|
//battery pause status begin
|
||||||
void setBatteryPause(bool pause_battery, bool pause_CAN, bool equipment_stop, bool store_settings) {
|
void setBatteryPause(bool pause_battery, bool pause_CAN, bool equipment_stop, bool store_settings) {
|
||||||
|
DEBUG_PRINTF("Battery pause begin %d %d %d %d\n", pause_battery, pause_CAN, equipment_stop, store_settings);
|
||||||
|
|
||||||
// First handle equipment stop / resume
|
// First handle equipment stop / resume
|
||||||
if (equipment_stop && !datalayer.system.settings.equipment_stop_active) {
|
if (equipment_stop && !datalayer.system.settings.equipment_stop_active) {
|
||||||
|
@ -394,17 +397,13 @@ void update_pause_state() {
|
||||||
allowed_to_send_CAN = (!emulator_pause_CAN_send_ON || emulator_pause_status == NORMAL);
|
allowed_to_send_CAN = (!emulator_pause_CAN_send_ON || emulator_pause_status == NORMAL);
|
||||||
|
|
||||||
if (previous_allowed_to_send_CAN && !allowed_to_send_CAN) {
|
if (previous_allowed_to_send_CAN && !allowed_to_send_CAN) {
|
||||||
#ifdef DEBUG_LOG
|
DEBUG_PRINTF("Safety: Pausing CAN sending\n");
|
||||||
logging.printf("Safety: Pausing CAN sending\n");
|
|
||||||
#endif
|
|
||||||
//completely force stop the CAN communication
|
//completely force stop the CAN communication
|
||||||
ESP32Can.CANStop(); //Note: This only stops the NATIVE_CAN port, it will no longer ACK messages
|
stop_can();
|
||||||
} else if (!previous_allowed_to_send_CAN && allowed_to_send_CAN) {
|
} else if (!previous_allowed_to_send_CAN && allowed_to_send_CAN) {
|
||||||
//resume CAN communication
|
//resume CAN communication
|
||||||
#ifdef DEBUG_LOG
|
DEBUG_PRINTF("Safety: Resuming CAN sending\n");
|
||||||
logging.printf("Safety: Resuming CAN sending\n");
|
restart_can();
|
||||||
#endif
|
|
||||||
ESP32Can.CANInit(); //Note: This only resumes the NATIVE_CAN port
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -1,8 +1,6 @@
|
||||||
#ifndef SAFETY_H
|
#ifndef SAFETY_H
|
||||||
#define SAFETY_H
|
#define SAFETY_H
|
||||||
#include <Arduino.h>
|
|
||||||
#include <string>
|
#include <string>
|
||||||
#include "../../lib/miwagner-ESP32-Arduino-CAN/ESP32CAN.h"
|
|
||||||
|
|
||||||
#define MAX_CAN_FAILURES 50
|
#define MAX_CAN_FAILURES 50
|
||||||
|
|
||||||
|
|
|
@ -1,9 +1,7 @@
|
||||||
#include "sdcard.h"
|
#include "sdcard.h"
|
||||||
|
#include "../../include.h"
|
||||||
#include "freertos/ringbuf.h"
|
#include "freertos/ringbuf.h"
|
||||||
|
|
||||||
#if defined(SD_CS_PIN) && defined(SD_SCLK_PIN) && defined(SD_MOSI_PIN) && \
|
|
||||||
defined(SD_MISO_PIN) // ensure code is only compiled if all SD card pins are defined
|
|
||||||
|
|
||||||
File can_log_file;
|
File can_log_file;
|
||||||
File log_file;
|
File log_file;
|
||||||
RingbufHandle_t can_bufferHandle;
|
RingbufHandle_t can_bufferHandle;
|
||||||
|
@ -185,17 +183,24 @@ void init_logging_buffers() {
|
||||||
#endif // defined(LOG_TO_SD)
|
#endif // defined(LOG_TO_SD)
|
||||||
}
|
}
|
||||||
|
|
||||||
void init_sdcard() {
|
bool init_sdcard() {
|
||||||
|
auto miso_pin = esp32hal->SD_MISO_PIN();
|
||||||
|
auto mosi_pin = esp32hal->SD_MOSI_PIN();
|
||||||
|
auto sclk_pin = esp32hal->SD_SCLK_PIN();
|
||||||
|
|
||||||
pinMode(SD_MISO_PIN, INPUT_PULLUP);
|
if (!esp32hal->alloc_pins("SD Card", miso_pin, mosi_pin, sclk_pin)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
SD_MMC.setPins(SD_SCLK_PIN, SD_MOSI_PIN, SD_MISO_PIN);
|
pinMode(miso_pin, INPUT_PULLUP);
|
||||||
|
|
||||||
|
SD_MMC.setPins(sclk_pin, mosi_pin, miso_pin);
|
||||||
if (!SD_MMC.begin("/root", true, true, SDMMC_FREQ_HIGHSPEED)) {
|
if (!SD_MMC.begin("/root", true, true, SDMMC_FREQ_HIGHSPEED)) {
|
||||||
set_event_latched(EVENT_SD_INIT_FAILED, 0);
|
set_event_latched(EVENT_SD_INIT_FAILED, 0);
|
||||||
#ifdef DEBUG_LOG
|
#ifdef DEBUG_LOG
|
||||||
logging.println("SD Card initialization failed!");
|
logging.println("SD Card initialization failed!");
|
||||||
#endif // DEBUG_LOG
|
#endif // DEBUG_LOG
|
||||||
return;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
clear_event(EVENT_SD_INIT_FAILED);
|
clear_event(EVENT_SD_INIT_FAILED);
|
||||||
|
@ -208,6 +213,8 @@ void init_sdcard() {
|
||||||
#ifdef DEBUG_LOG
|
#ifdef DEBUG_LOG
|
||||||
log_sdcard_details();
|
log_sdcard_details();
|
||||||
#endif // DEBUG_LOG
|
#endif // DEBUG_LOG
|
||||||
|
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
void log_sdcard_details() {
|
void log_sdcard_details() {
|
||||||
|
@ -245,4 +252,3 @@ void log_sdcard_details() {
|
||||||
logging.println(" MB");
|
logging.println(" MB");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif // defined(SD_CS_PIN) && defined(SD_SCLK_PIN) && defined(SD_MOSI_PIN) && defined(SD_MISO_PIN)
|
|
||||||
|
|
|
@ -6,14 +6,12 @@
|
||||||
#include "../hal/hal.h"
|
#include "../hal/hal.h"
|
||||||
#include "../utils/events.h"
|
#include "../utils/events.h"
|
||||||
|
|
||||||
#if defined(SD_CS_PIN) && defined(SD_SCLK_PIN) && defined(SD_MOSI_PIN) && \
|
|
||||||
defined(SD_MISO_PIN) // ensure code is only compiled if all SD card pins are defined
|
|
||||||
#define CAN_LOG_FILE "/canlog.txt"
|
#define CAN_LOG_FILE "/canlog.txt"
|
||||||
#define LOG_FILE "/log.txt"
|
#define LOG_FILE "/log.txt"
|
||||||
|
|
||||||
void init_logging_buffers();
|
void init_logging_buffers();
|
||||||
|
|
||||||
void init_sdcard();
|
bool init_sdcard();
|
||||||
void log_sdcard_details();
|
void log_sdcard_details();
|
||||||
|
|
||||||
void add_can_frame_to_buffer(CAN_frame frame, frameDirection msgDir);
|
void add_can_frame_to_buffer(CAN_frame frame, frameDirection msgDir);
|
||||||
|
@ -29,5 +27,4 @@ void pause_log_writing();
|
||||||
void add_log_to_buffer(const uint8_t* buffer, size_t size);
|
void add_log_to_buffer(const uint8_t* buffer, size_t size);
|
||||||
void write_log_to_sdcard();
|
void write_log_to_sdcard();
|
||||||
|
|
||||||
#endif // defined(SD_CS_PIN) && defined(SD_SCLK_PIN) && defined(SD_MOSI_PIN) && defined(SD_MISO_PIN)
|
|
||||||
#endif // SDCARD_H
|
#endif // SDCARD_H
|
||||||
|
|
|
@ -1,5 +1,6 @@
|
||||||
#include "events.h"
|
#include "events.h"
|
||||||
#include "../../datalayer/datalayer.h"
|
#include "../../datalayer/datalayer.h"
|
||||||
|
#include "../../include.h"
|
||||||
|
|
||||||
#include "../../../USER_SETTINGS.h"
|
#include "../../../USER_SETTINGS.h"
|
||||||
|
|
||||||
|
@ -124,6 +125,9 @@ void init_events(void) {
|
||||||
events.entries[EVENT_PERIODIC_BMS_RESET_AT_INIT_SUCCESS].level = EVENT_LEVEL_INFO;
|
events.entries[EVENT_PERIODIC_BMS_RESET_AT_INIT_SUCCESS].level = EVENT_LEVEL_INFO;
|
||||||
events.entries[EVENT_PERIODIC_BMS_RESET_AT_INIT_FAILED].level = EVENT_LEVEL_WARNING;
|
events.entries[EVENT_PERIODIC_BMS_RESET_AT_INIT_FAILED].level = EVENT_LEVEL_WARNING;
|
||||||
events.entries[EVENT_BATTERY_TEMP_DEVIATION_HIGH].level = EVENT_LEVEL_WARNING;
|
events.entries[EVENT_BATTERY_TEMP_DEVIATION_HIGH].level = EVENT_LEVEL_WARNING;
|
||||||
|
events.entries[EVENT_GPIO_CONFLICT].level = EVENT_LEVEL_ERROR;
|
||||||
|
events.entries[EVENT_GPIO_NOT_DEFINED].level = EVENT_LEVEL_ERROR;
|
||||||
|
events.entries[EVENT_BATTERY_TEMP_DEVIATION_HIGH].level = EVENT_LEVEL_WARNING;
|
||||||
}
|
}
|
||||||
|
|
||||||
void set_event(EVENTS_ENUM_TYPE event, uint8_t data) {
|
void set_event(EVENTS_ENUM_TYPE event, uint8_t data) {
|
||||||
|
@ -161,7 +165,7 @@ void set_event_MQTTpublished(EVENTS_ENUM_TYPE event) {
|
||||||
events.entries[event].MQTTpublished = true;
|
events.entries[event].MQTTpublished = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
const char* get_event_message_string(EVENTS_ENUM_TYPE event) {
|
String get_event_message_string(EVENTS_ENUM_TYPE event) {
|
||||||
switch (event) {
|
switch (event) {
|
||||||
case EVENT_CANMCP2517FD_INIT_FAILURE:
|
case EVENT_CANMCP2517FD_INIT_FAILURE:
|
||||||
return "CAN-FD initialization failed. Check hardware or bitrate settings";
|
return "CAN-FD initialization failed. Check hardware or bitrate settings";
|
||||||
|
@ -364,6 +368,12 @@ const char* get_event_message_string(EVENTS_ENUM_TYPE event) {
|
||||||
case EVENT_PERIODIC_BMS_RESET_AT_INIT_FAILED:
|
case EVENT_PERIODIC_BMS_RESET_AT_INIT_FAILED:
|
||||||
return "Failed to syncronise with the NTP Server. BMS will reset every 24 hours from when the emulator was "
|
return "Failed to syncronise with the NTP Server. BMS will reset every 24 hours from when the emulator was "
|
||||||
"powered on";
|
"powered on";
|
||||||
|
case EVENT_GPIO_CONFLICT:
|
||||||
|
return "GPIO Pin Conflict: The pin used by '" + esp32hal->failed_allocator() + "' is already allocated by '" +
|
||||||
|
esp32hal->conflicting_allocator() + "'. Please check your configuration and assign different pins.";
|
||||||
|
case EVENT_GPIO_NOT_DEFINED:
|
||||||
|
return "Missing GPIO Assignment: The component '" + esp32hal->failed_allocator() +
|
||||||
|
"' requires a GPIO pin that isn't configured. Please define a valid pin number in your settings.";
|
||||||
default:
|
default:
|
||||||
return "";
|
return "";
|
||||||
}
|
}
|
||||||
|
@ -402,10 +412,8 @@ static void set_event(EVENTS_ENUM_TYPE event, uint8_t data, bool latched) {
|
||||||
(events.entries[event].state != EVENT_STATE_ACTIVE_LATCHED)) {
|
(events.entries[event].state != EVENT_STATE_ACTIVE_LATCHED)) {
|
||||||
events.entries[event].occurences++;
|
events.entries[event].occurences++;
|
||||||
events.entries[event].MQTTpublished = false;
|
events.entries[event].MQTTpublished = false;
|
||||||
#ifdef DEBUG_LOG
|
|
||||||
logging.print("Event: ");
|
DEBUG_PRINTF("Event: %s\n", get_event_message_string(event).c_str());
|
||||||
logging.println(get_event_message_string(event));
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// We should set the event, update event info
|
// We should set the event, update event info
|
||||||
|
|
|
@ -1,8 +1,9 @@
|
||||||
#ifndef __EVENTS_H__
|
#ifndef __EVENTS_H__
|
||||||
#define __EVENTS_H__
|
#define __EVENTS_H__
|
||||||
#ifndef UNIT_TEST
|
|
||||||
#include "../../include.h"
|
#include <WString.h>
|
||||||
#endif
|
#include <src/devboard/utils/types.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
#define GENERATE_ENUM(ENUM) ENUM,
|
#define GENERATE_ENUM(ENUM) ENUM,
|
||||||
#define GENERATE_STRING(STRING) #STRING,
|
#define GENERATE_STRING(STRING) #STRING,
|
||||||
|
@ -107,6 +108,8 @@
|
||||||
XX(EVENT_PERIODIC_BMS_RESET_AT_INIT_SUCCESS) \
|
XX(EVENT_PERIODIC_BMS_RESET_AT_INIT_SUCCESS) \
|
||||||
XX(EVENT_PERIODIC_BMS_RESET_AT_INIT_FAILED) \
|
XX(EVENT_PERIODIC_BMS_RESET_AT_INIT_FAILED) \
|
||||||
XX(EVENT_BATTERY_TEMP_DEVIATION_HIGH) \
|
XX(EVENT_BATTERY_TEMP_DEVIATION_HIGH) \
|
||||||
|
XX(EVENT_GPIO_NOT_DEFINED) \
|
||||||
|
XX(EVENT_GPIO_CONFLICT) \
|
||||||
XX(EVENT_NOF_EVENTS)
|
XX(EVENT_NOF_EVENTS)
|
||||||
|
|
||||||
typedef enum { EVENTS_ENUM_TYPE(GENERATE_ENUM) } EVENTS_ENUM_TYPE;
|
typedef enum { EVENTS_ENUM_TYPE(GENERATE_ENUM) } EVENTS_ENUM_TYPE;
|
||||||
|
@ -144,7 +147,7 @@ struct EventData {
|
||||||
};
|
};
|
||||||
|
|
||||||
const char* get_event_enum_string(EVENTS_ENUM_TYPE event);
|
const char* get_event_enum_string(EVENTS_ENUM_TYPE event);
|
||||||
const char* get_event_message_string(EVENTS_ENUM_TYPE event);
|
String get_event_message_string(EVENTS_ENUM_TYPE event);
|
||||||
const char* get_event_level_string(EVENTS_ENUM_TYPE event);
|
const char* get_event_level_string(EVENTS_ENUM_TYPE event);
|
||||||
|
|
||||||
EVENTS_LEVEL_TYPE get_event_level(void);
|
EVENTS_LEVEL_TYPE get_event_level(void);
|
||||||
|
|
|
@ -16,16 +16,23 @@ static const float heartbeat_peak1 = 0.80;
|
||||||
static const float heartbeat_peak2 = 0.55;
|
static const float heartbeat_peak2 = 0.55;
|
||||||
static const float heartbeat_deviation = 0.05;
|
static const float heartbeat_deviation = 0.05;
|
||||||
|
|
||||||
static LED led(datalayer.battery.status.led_mode);
|
static LED* led;
|
||||||
|
|
||||||
void led_init(void) {
|
bool led_init(void) {
|
||||||
led.init();
|
if (!esp32hal->alloc_pins("LED", esp32hal->LED_PIN())) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
led = new LED(datalayer.battery.status.led_mode, esp32hal->LED_PIN(), esp32hal->LED_MAX_BRIGHTNESS());
|
||||||
|
led->init();
|
||||||
|
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
void led_exe(void) {
|
void led_exe(void) {
|
||||||
led.exe();
|
led->exe();
|
||||||
}
|
}
|
||||||
led_color led_get_color() {
|
led_color led_get_color() {
|
||||||
return led.color;
|
return led->color;
|
||||||
}
|
}
|
||||||
|
|
||||||
void LED::exe(void) {
|
void LED::exe(void) {
|
||||||
|
@ -61,7 +68,7 @@ void LED::exe(void) {
|
||||||
break;
|
break;
|
||||||
case EVENT_LEVEL_ERROR:
|
case EVENT_LEVEL_ERROR:
|
||||||
color = led_color::RED;
|
color = led_color::RED;
|
||||||
pixels.setPixelColor(0, COLOR_RED(LED_MAX_BRIGHTNESS)); // Red LED full brightness
|
pixels.setPixelColor(0, COLOR_RED(esp32hal->LED_MAX_BRIGHTNESS())); // Red LED full brightness
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
|
@ -126,7 +133,7 @@ void LED::heartbeat_run(void) {
|
||||||
brightness_f = map_float(period_pct, 0.55f, 1.00f, heartbeat_base + heartbeat_deviation * 2, heartbeat_base);
|
brightness_f = map_float(period_pct, 0.55f, 1.00f, heartbeat_base + heartbeat_deviation * 2, heartbeat_base);
|
||||||
}
|
}
|
||||||
|
|
||||||
brightness = (uint8_t)(brightness_f * LED_MAX_BRIGHTNESS);
|
brightness = (uint8_t)(brightness_f * esp32hal->LED_MAX_BRIGHTNESS());
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t LED::up_down(float middle_point_f) {
|
uint8_t LED::up_down(float middle_point_f) {
|
||||||
|
@ -138,7 +145,7 @@ uint8_t LED::up_down(float middle_point_f) {
|
||||||
if (ms < middle_point) {
|
if (ms < middle_point) {
|
||||||
brightness = map_uint16(ms, 0, middle_point, 0, max_brightness);
|
brightness = map_uint16(ms, 0, middle_point, 0, max_brightness);
|
||||||
} else {
|
} else {
|
||||||
brightness = LED_MAX_BRIGHTNESS - map_uint16(ms, middle_point, LED_PERIOD_MS, 0, max_brightness);
|
brightness = esp32hal->LED_MAX_BRIGHTNESS() - map_uint16(ms, middle_point, LED_PERIOD_MS, 0, max_brightness);
|
||||||
}
|
}
|
||||||
return CONSTRAIN(brightness, 0, max_brightness);
|
return CONSTRAIN(brightness, 0, max_brightness);
|
||||||
}
|
}
|
||||||
|
|
|
@ -8,14 +8,14 @@ class LED {
|
||||||
public:
|
public:
|
||||||
led_color color = led_color::GREEN;
|
led_color color = led_color::GREEN;
|
||||||
|
|
||||||
LED()
|
LED(gpio_num_t pin, uint8_t maxBrightness)
|
||||||
: pixels(1, LED_PIN, NEO_GRB),
|
: pixels(1, pin, NEO_GRB),
|
||||||
max_brightness(LED_MAX_BRIGHTNESS),
|
max_brightness(maxBrightness),
|
||||||
brightness(LED_MAX_BRIGHTNESS),
|
brightness(maxBrightness),
|
||||||
mode(led_mode_enum::CLASSIC) {}
|
mode(led_mode_enum::CLASSIC) {}
|
||||||
|
|
||||||
LED(led_mode_enum mode)
|
LED(led_mode_enum mode, gpio_num_t pin, uint8_t maxBrightness)
|
||||||
: pixels(1, LED_PIN, NEO_GRB), max_brightness(LED_MAX_BRIGHTNESS), brightness(LED_MAX_BRIGHTNESS), mode(mode) {}
|
: pixels(1, pin, NEO_GRB), max_brightness(maxBrightness), brightness(maxBrightness), mode(mode) {}
|
||||||
|
|
||||||
void exe(void);
|
void exe(void);
|
||||||
void init(void) { pixels.begin(); }
|
void init(void) { pixels.begin(); }
|
||||||
|
@ -33,7 +33,7 @@ class LED {
|
||||||
uint8_t up_down(float middle_point_f);
|
uint8_t up_down(float middle_point_f);
|
||||||
};
|
};
|
||||||
|
|
||||||
void led_init(void);
|
bool led_init(void);
|
||||||
void led_exe(void);
|
void led_exe(void);
|
||||||
led_color led_get_color(void);
|
led_color led_get_color(void);
|
||||||
|
|
||||||
|
|
|
@ -20,8 +20,10 @@ extern Logging logging;
|
||||||
|
|
||||||
#ifdef DEBUG_LOG
|
#ifdef DEBUG_LOG
|
||||||
#define DEBUG_PRINTF(fmt, ...) logging.printf(fmt, ##__VA_ARGS__)
|
#define DEBUG_PRINTF(fmt, ...) logging.printf(fmt, ##__VA_ARGS__)
|
||||||
|
#define DEBUG_PRINTLN(str) logging.println(str)
|
||||||
#else
|
#else
|
||||||
#define DEBUG_PRINTF(fmt, ...) ((void)0)
|
#define DEBUG_PRINTF(fmt, ...) ((void)0)
|
||||||
|
#define DEBUG_PRINTLN(fmt, ...) ((void)0)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#endif // __LOGGING_H__
|
#endif // __LOGGING_H__
|
||||||
|
|
|
@ -1,11 +1,26 @@
|
||||||
#ifndef _TYPES_H_
|
#ifndef _TYPES_H_
|
||||||
#define _TYPES_H_
|
#define _TYPES_H_
|
||||||
|
|
||||||
|
#include <chrono>
|
||||||
#include <string>
|
#include <string>
|
||||||
|
|
||||||
|
using milliseconds = std::chrono::milliseconds;
|
||||||
|
using duration = std::chrono::duration<unsigned long, std::ratio<1, 1000>>;
|
||||||
|
|
||||||
enum bms_status_enum { STANDBY = 0, INACTIVE = 1, DARKSTART = 2, ACTIVE = 3, FAULT = 4, UPDATING = 5 };
|
enum bms_status_enum { STANDBY = 0, INACTIVE = 1, DARKSTART = 2, ACTIVE = 3, FAULT = 4, UPDATING = 5 };
|
||||||
enum real_bms_status_enum { BMS_DISCONNECTED = 0, BMS_STANDBY = 1, BMS_ACTIVE = 2, BMS_FAULT = 3 };
|
enum real_bms_status_enum { BMS_DISCONNECTED = 0, BMS_STANDBY = 1, BMS_ACTIVE = 2, BMS_FAULT = 3 };
|
||||||
enum battery_chemistry_enum { NCA, NMC, LFP };
|
enum battery_chemistry_enum { NCA = 1, NMC = 2, LFP = 3, Highest };
|
||||||
|
|
||||||
|
enum class comm_interface {
|
||||||
|
Modbus = 1,
|
||||||
|
RS485 = 2,
|
||||||
|
CanNative = 3,
|
||||||
|
CanFdNative = 4,
|
||||||
|
CanAddonMcp2515 = 5,
|
||||||
|
CanFdAddonMcp2518 = 6,
|
||||||
|
Highest
|
||||||
|
};
|
||||||
|
|
||||||
enum led_color { GREEN, YELLOW, RED, BLUE };
|
enum led_color { GREEN, YELLOW, RED, BLUE };
|
||||||
enum led_mode_enum { CLASSIC, FLOW, HEARTBEAT };
|
enum led_mode_enum { CLASSIC, FLOW, HEARTBEAT };
|
||||||
enum PrechargeState {
|
enum PrechargeState {
|
||||||
|
@ -42,7 +57,20 @@ enum PrechargeState {
|
||||||
#define CAN_STILL_ALIVE 60
|
#define CAN_STILL_ALIVE 60
|
||||||
// Set by battery each time we get a CAN message. Decrements every second. When reaching 0, sets event
|
// Set by battery each time we get a CAN message. Decrements every second. When reaching 0, sets event
|
||||||
|
|
||||||
typedef enum { CAN_NATIVE = 0, CANFD_NATIVE = 1, CAN_ADDON_MCP2515 = 2, CANFD_ADDON_MCP2518 = 3 } CAN_Interface;
|
enum CAN_Interface {
|
||||||
|
// Native CAN port on the LilyGo & Stark hardware
|
||||||
|
CAN_NATIVE = 0,
|
||||||
|
|
||||||
|
// Native CANFD port on the Stark CMR hardware
|
||||||
|
CANFD_NATIVE = 1,
|
||||||
|
|
||||||
|
// Add-on CAN MCP2515 connected to GPIO pins
|
||||||
|
CAN_ADDON_MCP2515 = 2,
|
||||||
|
|
||||||
|
// Add-on CAN-FD MCP2518 connected to GPIO pins
|
||||||
|
CANFD_ADDON_MCP2518 = 3
|
||||||
|
};
|
||||||
|
|
||||||
extern const char* getCANInterfaceName(CAN_Interface interface);
|
extern const char* getCANInterfaceName(CAN_Interface interface);
|
||||||
|
|
||||||
/* CAN Frame structure */
|
/* CAN Frame structure */
|
||||||
|
|
|
@ -1,6 +1,7 @@
|
||||||
#include "events_html.h"
|
#include "events_html.h"
|
||||||
#include <limits>
|
#include <limits>
|
||||||
#include "../../datalayer/datalayer.h"
|
#include "../../datalayer/datalayer.h"
|
||||||
|
#include "../../devboard/utils/logging.h"
|
||||||
|
|
||||||
const char EVENTS_HTML_START[] = R"=====(
|
const char EVENTS_HTML_START[] = R"=====(
|
||||||
<style>body{background-color:#000;color:#fff}.event-log{display:flex;flex-direction:column}.event{display:flex;flex-wrap:wrap;border:1px solid #fff;padding:10px}.event>div{flex:1;min-width:100px;max-width:90%;word-break:break-word}</style><div style="background-color:#303e47;padding:10px;margin-bottom:10px;border-radius:25px"><div class="event-log"><div class="event" style="background-color:#1e2c33;font-weight:700"><div>Event Type</div><div>Severity</div><div>Last Event</div><div>Count</div><div>Data</div><div>Message</div></div>
|
<style>body{background-color:#000;color:#fff}.event-log{display:flex;flex-direction:column}.event{display:flex;flex-wrap:wrap;border:1px solid #fff;padding:10px}.event>div{flex:1;min-width:100px;max-width:90%;word-break:break-word}</style><div style="background-color:#303e47;padding:10px;margin-bottom:10px;border-radius:25px"><div class="event-log"><div class="event" style="background-color:#1e2c33;font-weight:700"><div>Event Type</div><div>Severity</div><div>Last Event</div><div>Count</div><div>Data</div><div>Message</div></div>
|
||||||
|
@ -59,7 +60,7 @@ String events_processor(const String& var) {
|
||||||
content.concat("<div class='sec-ago'>" + String(current_timestamp - event_pointer->timestamp) + "</div>");
|
content.concat("<div class='sec-ago'>" + String(current_timestamp - event_pointer->timestamp) + "</div>");
|
||||||
content.concat("<div>" + String(event_pointer->occurences) + "</div>");
|
content.concat("<div>" + String(event_pointer->occurences) + "</div>");
|
||||||
content.concat("<div>" + String(event_pointer->data) + "</div>");
|
content.concat("<div>" + String(event_pointer->data) + "</div>");
|
||||||
content.concat("<div>" + String(get_event_message_string(event_handle)) + "</div>");
|
content.concat("<div>" + get_event_message_string(event_handle) + "</div>");
|
||||||
content.concat("</div>"); // End of event row
|
content.concat("</div>"); // End of event row
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -1,10 +1,6 @@
|
||||||
#include "index_html.h"
|
#include "index_html.h"
|
||||||
|
|
||||||
#define INDEX_HTML_HEADER \
|
const char index_html[] = INDEX_HTML_HEADER COMMON_JAVASCRIPT "%X%" INDEX_HTML_FOOTER;
|
||||||
R"rawliteral(<!doctype html><html><head><title>Battery Emulator</title><meta content="width=device-width"name=viewport><style>html{font-family:Arial;display:inline-block;text-align:center}h2{font-size:3rem}body{max-width:800px;margin:0 auto}</style><body>)rawliteral"
|
|
||||||
#define INDEX_HTML_FOOTER R"rawliteral(</body></html>)rawliteral";
|
|
||||||
|
|
||||||
const char index_html[] = INDEX_HTML_HEADER "%X%" INDEX_HTML_FOOTER;
|
|
||||||
const char index_html_header[] = INDEX_HTML_HEADER;
|
const char index_html_header[] = INDEX_HTML_HEADER;
|
||||||
const char index_html_footer[] = INDEX_HTML_FOOTER;
|
const char index_html_footer[] = INDEX_HTML_FOOTER;
|
||||||
|
|
||||||
|
|
|
@ -1,6 +1,26 @@
|
||||||
#ifndef INDEX_HTML_H
|
#ifndef INDEX_HTML_H
|
||||||
#define INDEX_HTML_H
|
#define INDEX_HTML_H
|
||||||
|
|
||||||
|
#define INDEX_HTML_HEADER \
|
||||||
|
R"rawliteral(<!doctype html><html><head><title>Battery Emulator</title><meta content="width=device-width"name=viewport><style>html{font-family:Arial;display:inline-block;text-align:center}h2{font-size:3rem}body{max-width:800px;margin:0 auto}</style><body>)rawliteral"
|
||||||
|
#define INDEX_HTML_FOOTER R"rawliteral(</body></html>)rawliteral";
|
||||||
|
|
||||||
|
#define COMMON_JAVASCRIPT \
|
||||||
|
R"rawliteral(
|
||||||
|
<script>
|
||||||
|
function askReboot() {
|
||||||
|
if (window.confirm('Are you sure you want to reboot the emulator? NOTE: If emulator is handling contactors, they will open during reboot!')) {
|
||||||
|
reboot();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
function reboot() {
|
||||||
|
var xhr = new XMLHttpRequest();
|
||||||
|
xhr.open('GET', '/reboot', true);
|
||||||
|
xhr.send();
|
||||||
|
}
|
||||||
|
</script>
|
||||||
|
)rawliteral"
|
||||||
|
|
||||||
extern const char index_html[];
|
extern const char index_html[];
|
||||||
extern const char index_html_header[];
|
extern const char index_html_header[];
|
||||||
extern const char index_html_footer[];
|
extern const char index_html_footer[];
|
||||||
|
|
File diff suppressed because it is too large
Load diff
|
@ -8,6 +8,7 @@ extern std::string ssid;
|
||||||
extern std::string password;
|
extern std::string password;
|
||||||
|
|
||||||
#include "../../../USER_SETTINGS.h" // Needed for WiFi ssid and password
|
#include "../../../USER_SETTINGS.h" // Needed for WiFi ssid and password
|
||||||
|
#include "../../communication/nvm/comm_nvm.h"
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Replaces placeholder with content section in web page
|
* @brief Replaces placeholder with content section in web page
|
||||||
|
@ -16,7 +17,7 @@ extern std::string password;
|
||||||
*
|
*
|
||||||
* @return String
|
* @return String
|
||||||
*/
|
*/
|
||||||
String settings_processor(const String& var);
|
String settings_processor(const String& var, BatteryEmulatorSettingsStore& settings);
|
||||||
/**
|
/**
|
||||||
* @brief Maps the value to a string of characters
|
* @brief Maps the value to a string of characters
|
||||||
*
|
*
|
||||||
|
@ -26,4 +27,6 @@ String settings_processor(const String& var);
|
||||||
*/
|
*/
|
||||||
const char* getCANInterfaceName(CAN_Interface interface);
|
const char* getCANInterfaceName(CAN_Interface interface);
|
||||||
|
|
||||||
|
extern const char settings_html[];
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -16,8 +16,28 @@
|
||||||
#include "../utils/timer.h"
|
#include "../utils/timer.h"
|
||||||
#include "esp_task_wdt.h"
|
#include "esp_task_wdt.h"
|
||||||
|
|
||||||
|
#include <string>
|
||||||
|
extern std::string http_username;
|
||||||
|
extern std::string http_password;
|
||||||
|
|
||||||
void transmit_can_frame(CAN_frame* tx_frame, int interface);
|
void transmit_can_frame(CAN_frame* tx_frame, int interface);
|
||||||
|
|
||||||
|
#ifdef WEBSERVER
|
||||||
|
const bool webserver_enabled_default = true;
|
||||||
|
#else
|
||||||
|
const bool webserver_enabled_default = false;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
bool webserver_enabled = webserver_enabled_default; // Global flag to enable or disable the webserver
|
||||||
|
|
||||||
|
#ifndef COMMON_IMAGE
|
||||||
|
const bool webserver_auth_default = WEBSERVER_AUTH_REQUIRED;
|
||||||
|
#else
|
||||||
|
const bool webserver_auth_default = false;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
bool webserver_auth = webserver_auth_default;
|
||||||
|
|
||||||
// Create AsyncWebServer object on port 80
|
// Create AsyncWebServer object on port 80
|
||||||
AsyncWebServer server(80);
|
AsyncWebServer server(80);
|
||||||
|
|
||||||
|
@ -159,56 +179,54 @@ void canReplayTask(void* param) {
|
||||||
vTaskDelete(NULL);
|
vTaskDelete(NULL);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void def_route_with_auth(const char* uri, AsyncWebServer& serv, WebRequestMethodComposite method,
|
||||||
|
std::function<void(AsyncWebServerRequest*)> handler) {
|
||||||
|
serv.on(uri, method, [handler](AsyncWebServerRequest* request) {
|
||||||
|
if (webserver_auth && !request->authenticate(http_username.c_str(), http_password.c_str())) {
|
||||||
|
return request->requestAuthentication();
|
||||||
|
}
|
||||||
|
handler(request);
|
||||||
|
});
|
||||||
|
}
|
||||||
|
|
||||||
void init_webserver() {
|
void init_webserver() {
|
||||||
|
|
||||||
server.on("/logout", HTTP_GET, [](AsyncWebServerRequest* request) { request->send(401); });
|
server.on("/logout", HTTP_GET, [](AsyncWebServerRequest* request) { request->send(401); });
|
||||||
|
|
||||||
// Route for firmware info from ota update page
|
// Route for firmware info from ota update page
|
||||||
server.on("/GetFirmwareInfo", HTTP_GET, [](AsyncWebServerRequest* request) {
|
def_route_with_auth("/GetFirmwareInfo", server, HTTP_GET, [](AsyncWebServerRequest* request) {
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password))
|
|
||||||
return request->requestAuthentication();
|
|
||||||
request->send(200, "application/json", get_firmware_info_html, get_firmware_info_processor);
|
request->send(200, "application/json", get_firmware_info_html, get_firmware_info_processor);
|
||||||
});
|
});
|
||||||
|
|
||||||
// Route for root / web page
|
// Route for root / web page
|
||||||
server.on("/", HTTP_GET, [](AsyncWebServerRequest* request) {
|
def_route_with_auth("/", server, HTTP_GET,
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password))
|
[](AsyncWebServerRequest* request) { request->send(200, "text/html", index_html, processor); });
|
||||||
return request->requestAuthentication();
|
|
||||||
request->send(200, "text/html", index_html, processor);
|
|
||||||
});
|
|
||||||
|
|
||||||
// Route for going to settings web page
|
// Route for going to settings web page
|
||||||
server.on("/settings", HTTP_GET, [](AsyncWebServerRequest* request) {
|
def_route_with_auth("/settings", server, HTTP_GET, [](AsyncWebServerRequest* request) {
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password))
|
// Using make_shared to ensure lifetime for the settings object during send() lambda execution
|
||||||
return request->requestAuthentication();
|
auto settings = std::make_shared<BatteryEmulatorSettingsStore>(true);
|
||||||
request->send(200, "text/html", index_html, settings_processor);
|
|
||||||
|
request->send(200, "text/html", settings_html,
|
||||||
|
[settings](const String& content) { return settings_processor(content, *settings); });
|
||||||
});
|
});
|
||||||
|
|
||||||
// Route for going to advanced battery info web page
|
// Route for going to advanced battery info web page
|
||||||
server.on("/advanced", HTTP_GET, [](AsyncWebServerRequest* request) {
|
def_route_with_auth("/advanced", server, HTTP_GET, [](AsyncWebServerRequest* request) {
|
||||||
request->send(200, "text/html", index_html, advanced_battery_processor);
|
request->send(200, "text/html", index_html, advanced_battery_processor);
|
||||||
});
|
});
|
||||||
|
|
||||||
// Route for going to CAN logging web page
|
// Route for going to CAN logging web page
|
||||||
server.on("/canlog", HTTP_GET, [](AsyncWebServerRequest* request) {
|
def_route_with_auth("/canlog", server, HTTP_GET, [](AsyncWebServerRequest* request) {
|
||||||
AsyncWebServerResponse* response = request->beginResponse(200, "text/html", can_logger_processor());
|
request->send(request->beginResponse(200, "text/html", can_logger_processor()));
|
||||||
request->send(response);
|
|
||||||
});
|
});
|
||||||
|
|
||||||
// Route for going to CAN replay web page
|
// Route for going to CAN replay web page
|
||||||
server.on("/canreplay", HTTP_GET, [](AsyncWebServerRequest* request) {
|
def_route_with_auth("/canreplay", server, HTTP_GET, [](AsyncWebServerRequest* request) {
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password)) {
|
request->send(request->beginResponse(200, "text/html", can_replay_processor()));
|
||||||
return request->requestAuthentication();
|
|
||||||
}
|
|
||||||
AsyncWebServerResponse* response = request->beginResponse(200, "text/html", can_replay_processor());
|
|
||||||
request->send(response);
|
|
||||||
});
|
});
|
||||||
|
|
||||||
server.on("/startReplay", HTTP_GET, [](AsyncWebServerRequest* request) {
|
def_route_with_auth("/startReplay", server, HTTP_GET, [](AsyncWebServerRequest* request) {
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password)) {
|
|
||||||
return request->requestAuthentication();
|
|
||||||
}
|
|
||||||
|
|
||||||
// Prevent multiple replay tasks from being created
|
// Prevent multiple replay tasks from being created
|
||||||
if (isReplayRunning) {
|
if (isReplayRunning) {
|
||||||
request->send(400, "text/plain", "Replay already running!");
|
request->send(400, "text/plain", "Replay already running!");
|
||||||
|
@ -224,18 +242,14 @@ void init_webserver() {
|
||||||
});
|
});
|
||||||
|
|
||||||
// Route for stopping the CAN replay
|
// Route for stopping the CAN replay
|
||||||
server.on("/stopReplay", HTTP_GET, [](AsyncWebServerRequest* request) {
|
def_route_with_auth("/stopReplay", server, HTTP_GET, [](AsyncWebServerRequest* request) {
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password)) {
|
|
||||||
return request->requestAuthentication();
|
|
||||||
}
|
|
||||||
|
|
||||||
datalayer.system.info.loop_playback = false;
|
datalayer.system.info.loop_playback = false;
|
||||||
|
|
||||||
request->send(200, "text/plain", "CAN replay stopped!");
|
request->send(200, "text/plain", "CAN replay stopped!");
|
||||||
});
|
});
|
||||||
|
|
||||||
// Route to handle setting the CAN interface for CAN replay
|
// Route to handle setting the CAN interface for CAN replay
|
||||||
server.on("/setCANInterface", HTTP_GET, [](AsyncWebServerRequest* request) {
|
def_route_with_auth("/setCANInterface", server, HTTP_GET, [](AsyncWebServerRequest* request) {
|
||||||
if (request->hasParam("interface")) {
|
if (request->hasParam("interface")) {
|
||||||
String canInterface = request->getParam("interface")->value();
|
String canInterface = request->getParam("interface")->value();
|
||||||
|
|
||||||
|
@ -363,23 +377,17 @@ void init_webserver() {
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Route for going to cellmonitor web page
|
// Route for going to cellmonitor web page
|
||||||
server.on("/cellmonitor", HTTP_GET, [](AsyncWebServerRequest* request) {
|
def_route_with_auth("/cellmonitor", server, HTTP_GET, [](AsyncWebServerRequest* request) {
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password))
|
|
||||||
return request->requestAuthentication();
|
|
||||||
request->send(200, "text/html", index_html, cellmonitor_processor);
|
request->send(200, "text/html", index_html, cellmonitor_processor);
|
||||||
});
|
});
|
||||||
|
|
||||||
// Route for going to event log web page
|
// Route for going to event log web page
|
||||||
server.on("/events", HTTP_GET, [](AsyncWebServerRequest* request) {
|
def_route_with_auth("/events", server, HTTP_GET, [](AsyncWebServerRequest* request) {
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password))
|
|
||||||
return request->requestAuthentication();
|
|
||||||
request->send(200, "text/html", index_html, events_processor);
|
request->send(200, "text/html", index_html, events_processor);
|
||||||
});
|
});
|
||||||
|
|
||||||
// Route for clearing all events
|
// Route for clearing all events
|
||||||
server.on("/clearevents", HTTP_GET, [](AsyncWebServerRequest* request) {
|
def_route_with_auth("/clearevents", server, HTTP_GET, [](AsyncWebServerRequest* request) {
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password))
|
|
||||||
return request->requestAuthentication();
|
|
||||||
reset_all_events();
|
reset_all_events();
|
||||||
// Send back a response that includes an instant redirect to /events
|
// Send back a response that includes an instant redirect to /events
|
||||||
String response = "<html><body>";
|
String response = "<html><body>";
|
||||||
|
@ -388,23 +396,34 @@ void init_webserver() {
|
||||||
request->send(200, "text/html", response);
|
request->send(200, "text/html", response);
|
||||||
});
|
});
|
||||||
|
|
||||||
|
def_route_with_auth("/factoryReset", server, HTTP_POST, [](AsyncWebServerRequest* request) {
|
||||||
|
// Reset all settings to factory defaults
|
||||||
|
BatteryEmulatorSettingsStore settings;
|
||||||
|
settings.clearAll();
|
||||||
|
|
||||||
|
request->send(200, "text/html", "OK");
|
||||||
|
});
|
||||||
|
|
||||||
|
#ifdef COMMON_IMAGE
|
||||||
struct BoolSetting {
|
struct BoolSetting {
|
||||||
const char* name;
|
const char* name;
|
||||||
bool existingValue;
|
bool existingValue;
|
||||||
bool newValue;
|
bool newValue;
|
||||||
};
|
};
|
||||||
|
|
||||||
const char* boolSettingNames[] = {"DBLBTR", "CNTCTRL", "CNTCTRLDBL", "PWMCNTCTRL", "PERBMSRESET", "REMBMSRESET"};
|
const char* boolSettingNames[] = {
|
||||||
|
"DBLBTR", "CNTCTRL", "CNTCTRLDBL", "PWMCNTCTRL", "PERBMSRESET", "REMBMSRESET",
|
||||||
|
"CANFDASCAN", "WIFIAPENABLED", "MQTTENABLED", "HADISC", "MQTTTOPICS",
|
||||||
|
};
|
||||||
|
|
||||||
#ifdef COMMON_IMAGE
|
// Handles the form POST from UI to save settings of the common image
|
||||||
// Handles the form POST from UI to save certain settings: battery/inverter type and double battery on/off
|
|
||||||
server.on("/saveSettings", HTTP_POST, [boolSettingNames](AsyncWebServerRequest* request) {
|
server.on("/saveSettings", HTTP_POST, [boolSettingNames](AsyncWebServerRequest* request) {
|
||||||
BatteryEmulatorSettingsStore settings;
|
BatteryEmulatorSettingsStore settings;
|
||||||
|
|
||||||
std::vector<BoolSetting> boolSettings;
|
std::vector<BoolSetting> boolSettings;
|
||||||
|
|
||||||
for (auto& name : boolSettingNames) {
|
for (auto& name : boolSettingNames) {
|
||||||
boolSettings.push_back({name, settings.getBool(name), false});
|
boolSettings.push_back({name, settings.getBool(name, name == std::string("WIFIAPENABLED")), false});
|
||||||
}
|
}
|
||||||
|
|
||||||
int numParams = request->params();
|
int numParams = request->params();
|
||||||
|
@ -413,25 +432,56 @@ void init_webserver() {
|
||||||
if (p->name() == "inverter") {
|
if (p->name() == "inverter") {
|
||||||
auto type = static_cast<InverterProtocolType>(atoi(p->value().c_str()));
|
auto type = static_cast<InverterProtocolType>(atoi(p->value().c_str()));
|
||||||
settings.saveUInt("INVTYPE", (int)type);
|
settings.saveUInt("INVTYPE", (int)type);
|
||||||
|
} else if (p->name() == "INVCOMM") {
|
||||||
|
auto type = static_cast<comm_interface>(atoi(p->value().c_str()));
|
||||||
|
settings.saveUInt("INVCOMM", (int)type);
|
||||||
} else if (p->name() == "battery") {
|
} else if (p->name() == "battery") {
|
||||||
auto type = static_cast<BatteryType>(atoi(p->value().c_str()));
|
auto type = static_cast<BatteryType>(atoi(p->value().c_str()));
|
||||||
settings.saveUInt("BATTTYPE", (int)type);
|
settings.saveUInt("BATTTYPE", (int)type);
|
||||||
|
} else if (p->name() == "BATTCHEM") {
|
||||||
|
auto type = static_cast<battery_chemistry_enum>(atoi(p->value().c_str()));
|
||||||
|
settings.saveUInt("BATTCHEM", (int)type);
|
||||||
|
} else if (p->name() == "BATTCOMM") {
|
||||||
|
auto type = static_cast<comm_interface>(atoi(p->value().c_str()));
|
||||||
|
settings.saveUInt("BATTCOMM", (int)type);
|
||||||
} else if (p->name() == "charger") {
|
} else if (p->name() == "charger") {
|
||||||
auto type = static_cast<ChargerType>(atoi(p->value().c_str()));
|
auto type = static_cast<ChargerType>(atoi(p->value().c_str()));
|
||||||
settings.saveUInt("CHGTYPE", (int)type);
|
settings.saveUInt("CHGTYPE", (int)type);
|
||||||
} /*else if (p->name() == "dblbtr") {
|
} else if (p->name() == "CHGCOMM") {
|
||||||
newDoubleBattery = p->value() == "on";
|
auto type = static_cast<comm_interface>(atoi(p->value().c_str()));
|
||||||
} else if (p->name() == "contctrl") {
|
settings.saveUInt("CHGCOMM", (int)type);
|
||||||
settings.saveBool("CNTCTRL", p->value() == "on");
|
} else if (p->name() == "EQSTOP") {
|
||||||
} else if (p->name() == "contctrldbl") {
|
auto type = static_cast<STOP_BUTTON_BEHAVIOR>(atoi(p->value().c_str()));
|
||||||
settings.saveBool("CNTCTRLDBL", p->value() == "on");
|
settings.saveUInt("EQSTOP", (int)type);
|
||||||
} else if (p->name() == "pwmcontctrl") {
|
} else if (p->name() == "BATT2COMM") {
|
||||||
settings.saveBool("PWMCNTCTRL", p->value() == "on");
|
auto type = static_cast<comm_interface>(atoi(p->value().c_str()));
|
||||||
} else if (p->name() == "PERBMSRESET") {
|
settings.saveUInt("BATT2COMM", (int)type);
|
||||||
settings.saveBool("PERBMSRESET", p->value() == "on");
|
} else if (p->name() == "shunt") {
|
||||||
} else if (p->name() == "REMBMSRESET") {
|
auto type = static_cast<ShuntType>(atoi(p->value().c_str()));
|
||||||
settings.saveBool("REMBMSRESET", p->value() == "on");
|
settings.saveUInt("SHUNTTYPE", (int)type);
|
||||||
}*/
|
} else if (p->name() == "SHUNTCOMM") {
|
||||||
|
auto type = static_cast<comm_interface>(atoi(p->value().c_str()));
|
||||||
|
settings.saveUInt("SHUNTCOMM", (int)type);
|
||||||
|
} else if (p->name() == "HOSTNAME") {
|
||||||
|
settings.saveString("HOSTNAME", p->value().c_str());
|
||||||
|
} else if (p->name() == "MQTTSERVER") {
|
||||||
|
settings.saveString("MQTTSERVER", p->value().c_str());
|
||||||
|
} else if (p->name() == "MQTTPORT") {
|
||||||
|
auto port = atoi(p->value().c_str());
|
||||||
|
settings.saveUInt("MQTTPORT", port);
|
||||||
|
} else if (p->name() == "MQTTUSER") {
|
||||||
|
settings.saveString("MQTTUSER", p->value().c_str());
|
||||||
|
} else if (p->name() == "MQTTPASSWORD") {
|
||||||
|
settings.saveString("MQTTPASSWORD", p->value().c_str());
|
||||||
|
} else if (p->name() == "MQTTTOPIC") {
|
||||||
|
settings.saveString("MQTTTOPIC", p->value().c_str());
|
||||||
|
} else if (p->name() == "MQTTOBJIDPREFIX") {
|
||||||
|
settings.saveString("MQTTOBJIDPREFIX", p->value().c_str());
|
||||||
|
} else if (p->name() == "MQTTDEVICENAME") {
|
||||||
|
settings.saveString("MQTTDEVICENAME", p->value().c_str());
|
||||||
|
} else if (p->name() == "HADEVICEID") {
|
||||||
|
settings.saveString("HADEVICEID", p->value().c_str());
|
||||||
|
}
|
||||||
|
|
||||||
for (auto& boolSetting : boolSettings) {
|
for (auto& boolSetting : boolSettings) {
|
||||||
if (p->name() == boolSetting.name) {
|
if (p->name() == boolSetting.name) {
|
||||||
|
@ -446,16 +496,13 @@ void init_webserver() {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
settingsUpdated = true;
|
settingsUpdated = settings.were_settings_updated();
|
||||||
request->redirect("/settings");
|
request->redirect("/settings");
|
||||||
});
|
});
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Route for editing SSID
|
// Route for editing SSID
|
||||||
server.on("/updateSSID", HTTP_GET, [](AsyncWebServerRequest* request) {
|
def_route_with_auth("/updateSSID", server, HTTP_GET, [](AsyncWebServerRequest* request) {
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password))
|
|
||||||
return request->requestAuthentication();
|
|
||||||
|
|
||||||
if (request->hasParam("value")) {
|
if (request->hasParam("value")) {
|
||||||
String value = request->getParam("value")->value();
|
String value = request->getParam("value")->value();
|
||||||
if (value.length() <= 63) { // Check if SSID is within the allowable length
|
if (value.length() <= 63) { // Check if SSID is within the allowable length
|
||||||
|
@ -470,9 +517,7 @@ void init_webserver() {
|
||||||
}
|
}
|
||||||
});
|
});
|
||||||
// Route for editing Password
|
// Route for editing Password
|
||||||
server.on("/updatePassword", HTTP_GET, [](AsyncWebServerRequest* request) {
|
def_route_with_auth("/updatePassword", server, HTTP_GET, [](AsyncWebServerRequest* request) {
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password))
|
|
||||||
return request->requestAuthentication();
|
|
||||||
if (request->hasParam("value")) {
|
if (request->hasParam("value")) {
|
||||||
String value = request->getParam("value")->value();
|
String value = request->getParam("value")->value();
|
||||||
if (value.length() > 8) { // Check if password is within the allowable length
|
if (value.length() > 8) { // Check if password is within the allowable length
|
||||||
|
@ -487,132 +532,88 @@ void init_webserver() {
|
||||||
}
|
}
|
||||||
});
|
});
|
||||||
|
|
||||||
// Route for editing Sofar ID
|
auto update_string = [](const char* route, std::function<void(String)> setter,
|
||||||
server.on("/updateSofarID", HTTP_GET, [](AsyncWebServerRequest* request) {
|
std::function<bool(String)> validator = nullptr) {
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password))
|
def_route_with_auth(route, server, HTTP_GET, [&](AsyncWebServerRequest* request) {
|
||||||
return request->requestAuthentication();
|
|
||||||
if (request->hasParam("value")) {
|
if (request->hasParam("value")) {
|
||||||
String value = request->getParam("value")->value();
|
String value = request->getParam("value")->value();
|
||||||
datalayer.battery.settings.sofar_user_specified_battery_id = value.toInt();
|
|
||||||
store_settings();
|
if (validator && !validator(value)) {
|
||||||
|
request->send(400, "text/plain", "Invalid value");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
setter(value);
|
||||||
request->send(200, "text/plain", "Updated successfully");
|
request->send(200, "text/plain", "Updated successfully");
|
||||||
} else {
|
} else {
|
||||||
request->send(400, "text/plain", "Bad Request");
|
request->send(400, "text/plain", "Bad Request");
|
||||||
}
|
}
|
||||||
});
|
});
|
||||||
|
};
|
||||||
|
|
||||||
|
auto update_string_setting = [=](const char* route, std::function<void(String)> setter,
|
||||||
|
std::function<bool(String)> validator = nullptr) {
|
||||||
|
update_string(
|
||||||
|
route,
|
||||||
|
[setter](String value) {
|
||||||
|
setter(value);
|
||||||
|
store_settings();
|
||||||
|
},
|
||||||
|
validator);
|
||||||
|
};
|
||||||
|
|
||||||
|
auto update_int_setting = [=](const char* route, std::function<void(int)> setter) {
|
||||||
|
update_string_setting(route, [setter](String value) { setter(value.toInt()); });
|
||||||
|
};
|
||||||
|
|
||||||
|
// Route for editing Sofar ID
|
||||||
|
update_int_setting("/updateSofarID",
|
||||||
|
[](int value) { datalayer.battery.settings.sofar_user_specified_battery_id = value; });
|
||||||
|
|
||||||
// Route for editing Wh
|
// Route for editing Wh
|
||||||
server.on("/updateBatterySize", HTTP_GET, [](AsyncWebServerRequest* request) {
|
update_int_setting("/updateBatterySize", [](int value) { datalayer.battery.info.total_capacity_Wh = value; });
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password))
|
|
||||||
return request->requestAuthentication();
|
|
||||||
if (request->hasParam("value")) {
|
|
||||||
String value = request->getParam("value")->value();
|
|
||||||
datalayer.battery.info.total_capacity_Wh = value.toInt();
|
|
||||||
store_settings();
|
|
||||||
request->send(200, "text/plain", "Updated successfully");
|
|
||||||
} else {
|
|
||||||
request->send(400, "text/plain", "Bad Request");
|
|
||||||
}
|
|
||||||
});
|
|
||||||
|
|
||||||
// Route for editing USE_SCALED_SOC
|
// Route for editing USE_SCALED_SOC
|
||||||
server.on("/updateUseScaledSOC", HTTP_GET, [](AsyncWebServerRequest* request) {
|
update_int_setting("/updateUseScaledSOC", [](int value) { datalayer.battery.settings.soc_scaling_active = value; });
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password))
|
|
||||||
return request->requestAuthentication();
|
|
||||||
if (request->hasParam("value")) {
|
|
||||||
String value = request->getParam("value")->value();
|
|
||||||
datalayer.battery.settings.soc_scaling_active = value.toInt();
|
|
||||||
store_settings();
|
|
||||||
request->send(200, "text/plain", "Updated successfully");
|
|
||||||
} else {
|
|
||||||
request->send(400, "text/plain", "Bad Request");
|
|
||||||
}
|
|
||||||
});
|
|
||||||
|
|
||||||
// Route for editing SOCMax
|
// Route for editing SOCMax
|
||||||
server.on("/updateSocMax", HTTP_GET, [](AsyncWebServerRequest* request) {
|
update_string_setting("/updateSocMax", [](String value) {
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password))
|
|
||||||
return request->requestAuthentication();
|
|
||||||
if (request->hasParam("value")) {
|
|
||||||
String value = request->getParam("value")->value();
|
|
||||||
datalayer.battery.settings.max_percentage = static_cast<uint16_t>(value.toFloat() * 100);
|
datalayer.battery.settings.max_percentage = static_cast<uint16_t>(value.toFloat() * 100);
|
||||||
store_settings();
|
|
||||||
request->send(200, "text/plain", "Updated successfully");
|
|
||||||
} else {
|
|
||||||
request->send(400, "text/plain", "Bad Request");
|
|
||||||
}
|
|
||||||
});
|
});
|
||||||
|
|
||||||
// Route for pause/resume Battery emulator
|
// Route for pause/resume Battery emulator
|
||||||
server.on("/pause", HTTP_GET, [](AsyncWebServerRequest* request) {
|
update_string("/pause", [](String value) { setBatteryPause(value == "true" || value == "1", false); });
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password))
|
|
||||||
return request->requestAuthentication();
|
|
||||||
if (request->hasParam("p")) {
|
|
||||||
String valueStr = request->getParam("p")->value();
|
|
||||||
setBatteryPause(valueStr == "true" || valueStr == "1", false);
|
|
||||||
request->send(200, "text/plain", "Updated successfully");
|
|
||||||
} else {
|
|
||||||
request->send(400, "text/plain", "Bad Request");
|
|
||||||
}
|
|
||||||
});
|
|
||||||
|
|
||||||
// Route for equipment stop/resume
|
// Route for equipment stop/resume
|
||||||
server.on("/equipmentStop", HTTP_GET, [](AsyncWebServerRequest* request) {
|
update_string("/equipmentStop", [](String value) {
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password))
|
if (value == "true" || value == "1") {
|
||||||
return request->requestAuthentication();
|
|
||||||
if (request->hasParam("stop")) {
|
|
||||||
String valueStr = request->getParam("stop")->value();
|
|
||||||
if (valueStr == "true" || valueStr == "1") {
|
|
||||||
setBatteryPause(true, false, true); //Pause battery, do not pause CAN, equipment stop on (store to flash)
|
setBatteryPause(true, false, true); //Pause battery, do not pause CAN, equipment stop on (store to flash)
|
||||||
} else {
|
} else {
|
||||||
setBatteryPause(false, false, false);
|
setBatteryPause(false, false, false);
|
||||||
}
|
}
|
||||||
request->send(200, "text/plain", "Updated successfully");
|
});
|
||||||
|
|
||||||
|
update_string("/equipmentStop", [](String value) {
|
||||||
|
if (value == "true" || value == "1") {
|
||||||
|
setBatteryPause(true, false, true); //Pause battery, do not pause CAN, equipment stop on (store to flash)
|
||||||
} else {
|
} else {
|
||||||
request->send(400, "text/plain", "Bad Request");
|
setBatteryPause(false, false, false);
|
||||||
}
|
}
|
||||||
});
|
});
|
||||||
|
|
||||||
// Route for editing SOCMin
|
// Route for editing SOCMin
|
||||||
server.on("/updateSocMin", HTTP_GET, [](AsyncWebServerRequest* request) {
|
update_string_setting("/updateSocMin", [](String value) {
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password))
|
|
||||||
return request->requestAuthentication();
|
|
||||||
if (request->hasParam("value")) {
|
|
||||||
String value = request->getParam("value")->value();
|
|
||||||
datalayer.battery.settings.min_percentage = static_cast<uint16_t>(value.toFloat() * 100);
|
datalayer.battery.settings.min_percentage = static_cast<uint16_t>(value.toFloat() * 100);
|
||||||
store_settings();
|
|
||||||
request->send(200, "text/plain", "Updated successfully");
|
|
||||||
} else {
|
|
||||||
request->send(400, "text/plain", "Bad Request");
|
|
||||||
}
|
|
||||||
});
|
});
|
||||||
|
|
||||||
// Route for editing MaxChargeA
|
// Route for editing MaxChargeA
|
||||||
server.on("/updateMaxChargeA", HTTP_GET, [](AsyncWebServerRequest* request) {
|
update_string_setting("/updateMaxChargeA", [](String value) {
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password))
|
|
||||||
return request->requestAuthentication();
|
|
||||||
if (request->hasParam("value")) {
|
|
||||||
String value = request->getParam("value")->value();
|
|
||||||
datalayer.battery.settings.max_user_set_charge_dA = static_cast<uint16_t>(value.toFloat() * 10);
|
datalayer.battery.settings.max_user_set_charge_dA = static_cast<uint16_t>(value.toFloat() * 10);
|
||||||
store_settings();
|
|
||||||
request->send(200, "text/plain", "Updated successfully");
|
|
||||||
} else {
|
|
||||||
request->send(400, "text/plain", "Bad Request");
|
|
||||||
}
|
|
||||||
});
|
});
|
||||||
|
|
||||||
// Route for editing MaxDischargeA
|
// Route for editing MaxDischargeA
|
||||||
server.on("/updateMaxDischargeA", HTTP_GET, [](AsyncWebServerRequest* request) {
|
update_string_setting("/updateMaxDischargeA", [](String value) {
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password))
|
|
||||||
return request->requestAuthentication();
|
|
||||||
if (request->hasParam("value")) {
|
|
||||||
String value = request->getParam("value")->value();
|
|
||||||
datalayer.battery.settings.max_user_set_discharge_dA = static_cast<uint16_t>(value.toFloat() * 10);
|
datalayer.battery.settings.max_user_set_discharge_dA = static_cast<uint16_t>(value.toFloat() * 10);
|
||||||
store_settings();
|
|
||||||
request->send(200, "text/plain", "Updated successfully");
|
|
||||||
} else {
|
|
||||||
request->send(400, "text/plain", "Bad Request");
|
|
||||||
}
|
|
||||||
});
|
});
|
||||||
|
|
||||||
for (const auto& cmd : battery_commands) {
|
for (const auto& cmd : battery_commands) {
|
||||||
|
@ -620,7 +621,7 @@ void init_webserver() {
|
||||||
server.on(
|
server.on(
|
||||||
route.c_str(), HTTP_PUT,
|
route.c_str(), HTTP_PUT,
|
||||||
[cmd](AsyncWebServerRequest* request) {
|
[cmd](AsyncWebServerRequest* request) {
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password)) {
|
if (webserver_auth && !request->authenticate(http_username.c_str(), http_password.c_str())) {
|
||||||
return request->requestAuthentication();
|
return request->requestAuthentication();
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
|
@ -642,247 +643,88 @@ void init_webserver() {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Route for editing BATTERY_USE_VOLTAGE_LIMITS
|
// Route for editing BATTERY_USE_VOLTAGE_LIMITS
|
||||||
server.on("/updateUseVoltageLimit", HTTP_GET, [](AsyncWebServerRequest* request) {
|
update_int_setting("/updateUseVoltageLimit",
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password))
|
[](int value) { datalayer.battery.settings.user_set_voltage_limits_active = value; });
|
||||||
return request->requestAuthentication();
|
|
||||||
if (request->hasParam("value")) {
|
|
||||||
String value = request->getParam("value")->value();
|
|
||||||
datalayer.battery.settings.user_set_voltage_limits_active = value.toInt();
|
|
||||||
store_settings();
|
|
||||||
request->send(200, "text/plain", "Updated successfully");
|
|
||||||
} else {
|
|
||||||
request->send(400, "text/plain", "Bad Request");
|
|
||||||
}
|
|
||||||
});
|
|
||||||
|
|
||||||
// Route for editing MaxChargeVoltage
|
// Route for editing MaxChargeVoltage
|
||||||
server.on("/updateMaxChargeVoltage", HTTP_GET, [](AsyncWebServerRequest* request) {
|
update_string_setting("/updateMaxChargeVoltage", [](String value) {
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password))
|
|
||||||
return request->requestAuthentication();
|
|
||||||
if (request->hasParam("value")) {
|
|
||||||
String value = request->getParam("value")->value();
|
|
||||||
datalayer.battery.settings.max_user_set_charge_voltage_dV = static_cast<uint16_t>(value.toFloat() * 10);
|
datalayer.battery.settings.max_user_set_charge_voltage_dV = static_cast<uint16_t>(value.toFloat() * 10);
|
||||||
store_settings();
|
|
||||||
request->send(200, "text/plain", "Updated successfully");
|
|
||||||
} else {
|
|
||||||
request->send(400, "text/plain", "Bad Request");
|
|
||||||
}
|
|
||||||
});
|
});
|
||||||
|
|
||||||
// Route for editing MaxDischargeVoltage
|
// Route for editing MaxDischargeVoltage
|
||||||
server.on("/updateMaxDischargeVoltage", HTTP_GET, [](AsyncWebServerRequest* request) {
|
update_string_setting("/updateMaxDischargeVoltage", [](String value) {
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password))
|
|
||||||
return request->requestAuthentication();
|
|
||||||
if (request->hasParam("value")) {
|
|
||||||
String value = request->getParam("value")->value();
|
|
||||||
datalayer.battery.settings.max_user_set_discharge_voltage_dV = static_cast<uint16_t>(value.toFloat() * 10);
|
datalayer.battery.settings.max_user_set_discharge_voltage_dV = static_cast<uint16_t>(value.toFloat() * 10);
|
||||||
store_settings();
|
|
||||||
request->send(200, "text/plain", "Updated successfully");
|
|
||||||
} else {
|
|
||||||
request->send(400, "text/plain", "Bad Request");
|
|
||||||
}
|
|
||||||
});
|
});
|
||||||
|
|
||||||
// Route for editing FakeBatteryVoltage
|
// Route for editing FakeBatteryVoltage
|
||||||
server.on("/updateFakeBatteryVoltage", HTTP_GET, [](AsyncWebServerRequest* request) {
|
update_string_setting("/updateFakeBatteryVoltage", [](String value) { battery->set_fake_voltage(value.toFloat()); });
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password))
|
|
||||||
return request->requestAuthentication();
|
|
||||||
if (!request->hasParam("value")) {
|
|
||||||
request->send(400, "text/plain", "Bad Request");
|
|
||||||
}
|
|
||||||
|
|
||||||
String value = request->getParam("value")->value();
|
|
||||||
float val = value.toFloat();
|
|
||||||
|
|
||||||
battery->set_fake_voltage(val);
|
|
||||||
|
|
||||||
request->send(200, "text/plain", "Updated successfully");
|
|
||||||
});
|
|
||||||
|
|
||||||
// Route for editing balancing enabled
|
// Route for editing balancing enabled
|
||||||
server.on("/TeslaBalAct", HTTP_GET, [](AsyncWebServerRequest* request) {
|
update_int_setting("/TeslaBalAct", [](int value) { datalayer.battery.settings.user_requests_balancing = value; });
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password))
|
|
||||||
return request->requestAuthentication();
|
|
||||||
if (request->hasParam("value")) {
|
|
||||||
String value = request->getParam("value")->value();
|
|
||||||
datalayer.battery.settings.user_requests_balancing = value.toInt();
|
|
||||||
store_settings();
|
|
||||||
request->send(200, "text/plain", "Updated successfully");
|
|
||||||
} else {
|
|
||||||
request->send(400, "text/plain", "Bad Request");
|
|
||||||
}
|
|
||||||
});
|
|
||||||
|
|
||||||
// Route for editing balancing max time
|
// Route for editing balancing max time
|
||||||
server.on("/BalTime", HTTP_GET, [](AsyncWebServerRequest* request) {
|
update_string_setting("/BalTime", [](String value) {
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password))
|
|
||||||
return request->requestAuthentication();
|
|
||||||
if (request->hasParam("value")) {
|
|
||||||
String value = request->getParam("value")->value();
|
|
||||||
datalayer.battery.settings.balancing_time_ms = static_cast<uint32_t>(value.toFloat() * 60000);
|
datalayer.battery.settings.balancing_time_ms = static_cast<uint32_t>(value.toFloat() * 60000);
|
||||||
store_settings();
|
|
||||||
request->send(200, "text/plain", "Updated successfully");
|
|
||||||
} else {
|
|
||||||
request->send(400, "text/plain", "Bad Request");
|
|
||||||
}
|
|
||||||
});
|
});
|
||||||
|
|
||||||
// Route for editing balancing max power
|
// Route for editing balancing max power
|
||||||
server.on("/BalFloatPower", HTTP_GET, [](AsyncWebServerRequest* request) {
|
update_string_setting("/BalFloatPower", [](String value) {
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password))
|
|
||||||
return request->requestAuthentication();
|
|
||||||
if (request->hasParam("value")) {
|
|
||||||
String value = request->getParam("value")->value();
|
|
||||||
datalayer.battery.settings.balancing_float_power_W = static_cast<uint16_t>(value.toFloat());
|
datalayer.battery.settings.balancing_float_power_W = static_cast<uint16_t>(value.toFloat());
|
||||||
store_settings();
|
|
||||||
request->send(200, "text/plain", "Updated successfully");
|
|
||||||
} else {
|
|
||||||
request->send(400, "text/plain", "Bad Request");
|
|
||||||
}
|
|
||||||
});
|
});
|
||||||
|
|
||||||
// Route for editing balancing max pack voltage
|
// Route for editing balancing max pack voltage
|
||||||
server.on("/BalMaxPackV", HTTP_GET, [](AsyncWebServerRequest* request) {
|
update_string_setting("/BalMaxPackV", [](String value) {
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password))
|
|
||||||
return request->requestAuthentication();
|
|
||||||
if (request->hasParam("value")) {
|
|
||||||
String value = request->getParam("value")->value();
|
|
||||||
datalayer.battery.settings.balancing_max_pack_voltage_dV = static_cast<uint16_t>(value.toFloat() * 10);
|
datalayer.battery.settings.balancing_max_pack_voltage_dV = static_cast<uint16_t>(value.toFloat() * 10);
|
||||||
store_settings();
|
|
||||||
request->send(200, "text/plain", "Updated successfully");
|
|
||||||
} else {
|
|
||||||
request->send(400, "text/plain", "Bad Request");
|
|
||||||
}
|
|
||||||
});
|
});
|
||||||
|
|
||||||
// Route for editing balancing max cell voltage
|
// Route for editing balancing max cell voltage
|
||||||
server.on("/BalMaxCellV", HTTP_GET, [](AsyncWebServerRequest* request) {
|
update_string_setting("/BalMaxCellV", [](String value) {
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password))
|
|
||||||
return request->requestAuthentication();
|
|
||||||
if (request->hasParam("value")) {
|
|
||||||
String value = request->getParam("value")->value();
|
|
||||||
datalayer.battery.settings.balancing_max_cell_voltage_mV = static_cast<uint16_t>(value.toFloat());
|
datalayer.battery.settings.balancing_max_cell_voltage_mV = static_cast<uint16_t>(value.toFloat());
|
||||||
store_settings();
|
|
||||||
request->send(200, "text/plain", "Updated successfully");
|
|
||||||
} else {
|
|
||||||
request->send(400, "text/plain", "Bad Request");
|
|
||||||
}
|
|
||||||
});
|
});
|
||||||
|
|
||||||
// Route for editing balancing max cell voltage deviation
|
// Route for editing balancing max cell voltage deviation
|
||||||
server.on("/BalMaxDevCellV", HTTP_GET, [](AsyncWebServerRequest* request) {
|
update_string_setting("/BalMaxDevCellV", [](String value) {
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password))
|
|
||||||
return request->requestAuthentication();
|
|
||||||
if (request->hasParam("value")) {
|
|
||||||
String value = request->getParam("value")->value();
|
|
||||||
datalayer.battery.settings.balancing_max_deviation_cell_voltage_mV = static_cast<uint16_t>(value.toFloat());
|
datalayer.battery.settings.balancing_max_deviation_cell_voltage_mV = static_cast<uint16_t>(value.toFloat());
|
||||||
store_settings();
|
|
||||||
request->send(200, "text/plain", "Updated successfully");
|
|
||||||
} else {
|
|
||||||
request->send(400, "text/plain", "Bad Request");
|
|
||||||
}
|
|
||||||
});
|
});
|
||||||
|
|
||||||
if (charger) {
|
if (charger) {
|
||||||
// Route for editing ChargerTargetV
|
// Route for editing ChargerTargetV
|
||||||
server.on("/updateChargeSetpointV", HTTP_GET, [](AsyncWebServerRequest* request) {
|
update_string_setting(
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password))
|
"/updateChargeSetpointV", [](String value) { datalayer.charger.charger_setpoint_HV_VDC = value.toFloat(); },
|
||||||
return request->requestAuthentication();
|
[](String value) {
|
||||||
if (!request->hasParam("value")) {
|
|
||||||
request->send(400, "text/plain", "Bad Request");
|
|
||||||
}
|
|
||||||
|
|
||||||
String value = request->getParam("value")->value();
|
|
||||||
float val = value.toFloat();
|
float val = value.toFloat();
|
||||||
|
return (val <= CHARGER_MAX_HV && val >= CHARGER_MIN_HV) &&
|
||||||
if (!(val <= CHARGER_MAX_HV && val >= CHARGER_MIN_HV)) {
|
(val * datalayer.charger.charger_setpoint_HV_IDC <= CHARGER_MAX_POWER);
|
||||||
request->send(400, "text/plain", "Bad Request");
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!(val * datalayer.charger.charger_setpoint_HV_IDC <= CHARGER_MAX_POWER)) {
|
|
||||||
request->send(400, "text/plain", "Bad Request");
|
|
||||||
}
|
|
||||||
|
|
||||||
datalayer.charger.charger_setpoint_HV_VDC = val;
|
|
||||||
|
|
||||||
request->send(200, "text/plain", "Updated successfully");
|
|
||||||
});
|
});
|
||||||
|
|
||||||
// Route for editing ChargerTargetA
|
// Route for editing ChargerTargetA
|
||||||
server.on("/updateChargeSetpointA", HTTP_GET, [](AsyncWebServerRequest* request) {
|
update_string_setting(
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password))
|
"/updateChargeSetpointA", [](String value) { datalayer.charger.charger_setpoint_HV_IDC = value.toFloat(); },
|
||||||
return request->requestAuthentication();
|
[](String value) {
|
||||||
if (!request->hasParam("value")) {
|
|
||||||
request->send(400, "text/plain", "Bad Request");
|
|
||||||
}
|
|
||||||
|
|
||||||
String value = request->getParam("value")->value();
|
|
||||||
float val = value.toFloat();
|
float val = value.toFloat();
|
||||||
|
return (val <= CHARGER_MAX_A) && (val <= datalayer.battery.settings.max_user_set_charge_dA) &&
|
||||||
if (!(val <= datalayer.battery.settings.max_user_set_charge_dA && val <= CHARGER_MAX_A)) {
|
(val * datalayer.charger.charger_setpoint_HV_VDC <= CHARGER_MAX_POWER);
|
||||||
request->send(400, "text/plain", "Bad Request");
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!(val * datalayer.charger.charger_setpoint_HV_VDC <= CHARGER_MAX_POWER)) {
|
|
||||||
request->send(400, "text/plain", "Bad Request");
|
|
||||||
}
|
|
||||||
|
|
||||||
datalayer.charger.charger_setpoint_HV_IDC = value.toFloat();
|
|
||||||
|
|
||||||
request->send(200, "text/plain", "Updated successfully");
|
|
||||||
});
|
});
|
||||||
|
|
||||||
// Route for editing ChargerEndA
|
// Route for editing ChargerEndA
|
||||||
server.on("/updateChargeEndA", HTTP_GET, [](AsyncWebServerRequest* request) {
|
update_string_setting("/updateChargeEndA",
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password))
|
[](String value) { datalayer.charger.charger_setpoint_HV_IDC_END = value.toFloat(); });
|
||||||
return request->requestAuthentication();
|
|
||||||
if (request->hasParam("value")) {
|
|
||||||
String value = request->getParam("value")->value();
|
|
||||||
datalayer.charger.charger_setpoint_HV_IDC_END = value.toFloat();
|
|
||||||
request->send(200, "text/plain", "Updated successfully");
|
|
||||||
} else {
|
|
||||||
request->send(400, "text/plain", "Bad Request");
|
|
||||||
}
|
|
||||||
});
|
|
||||||
|
|
||||||
// Route for enabling/disabling HV charger
|
// Route for enabling/disabling HV charger
|
||||||
server.on("/updateChargerHvEnabled", HTTP_GET, [](AsyncWebServerRequest* request) {
|
update_int_setting("/updateChargerHvEnabled",
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password))
|
[](int value) { datalayer.charger.charger_HV_enabled = (bool)value; });
|
||||||
return request->requestAuthentication();
|
|
||||||
if (request->hasParam("value")) {
|
|
||||||
String value = request->getParam("value")->value();
|
|
||||||
datalayer.charger.charger_HV_enabled = (bool)value.toInt();
|
|
||||||
request->send(200, "text/plain", "Updated successfully");
|
|
||||||
} else {
|
|
||||||
request->send(400, "text/plain", "Bad Request");
|
|
||||||
}
|
|
||||||
});
|
|
||||||
|
|
||||||
// Route for enabling/disabling aux12v charger
|
// Route for enabling/disabling aux12v charger
|
||||||
server.on("/updateChargerAux12vEnabled", HTTP_GET, [](AsyncWebServerRequest* request) {
|
update_int_setting("/updateChargerAux12vEnabled",
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password))
|
[](int value) { datalayer.charger.charger_aux12V_enabled = (bool)value; });
|
||||||
return request->requestAuthentication();
|
|
||||||
if (request->hasParam("value")) {
|
|
||||||
String value = request->getParam("value")->value();
|
|
||||||
datalayer.charger.charger_aux12V_enabled = (bool)value.toInt();
|
|
||||||
request->send(200, "text/plain", "Updated successfully");
|
|
||||||
} else {
|
|
||||||
request->send(400, "text/plain", "Bad Request");
|
|
||||||
}
|
|
||||||
});
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Send a GET request to <ESP_IP>/update
|
// Send a GET request to <ESP_IP>/update
|
||||||
server.on("/debug", HTTP_GET, [](AsyncWebServerRequest* request) {
|
def_route_with_auth("/debug", server, HTTP_GET,
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password))
|
[](AsyncWebServerRequest* request) { request->send(200, "text/plain", "Debug: all OK."); });
|
||||||
return request->requestAuthentication();
|
|
||||||
request->send(200, "text/plain", "Debug: all OK.");
|
|
||||||
});
|
|
||||||
|
|
||||||
// Route to handle reboot command
|
// Route to handle reboot command
|
||||||
server.on("/reboot", HTTP_GET, [](AsyncWebServerRequest* request) {
|
def_route_with_auth("/reboot", server, HTTP_GET, [](AsyncWebServerRequest* request) {
|
||||||
if (WEBSERVER_AUTH_REQUIRED && !request->authenticate(http_username, http_password))
|
|
||||||
return request->requestAuthentication();
|
|
||||||
request->send(200, "text/plain", "Rebooting server...");
|
request->send(200, "text/plain", "Rebooting server...");
|
||||||
|
|
||||||
//Equipment STOP without persisting the equipment state before restart
|
//Equipment STOP without persisting the equipment state before restart
|
||||||
|
@ -943,19 +785,8 @@ String get_firmware_info_processor(const String& var) {
|
||||||
if (var == "X") {
|
if (var == "X") {
|
||||||
String content = "";
|
String content = "";
|
||||||
static JsonDocument doc;
|
static JsonDocument doc;
|
||||||
#ifdef HW_LILYGO
|
|
||||||
doc["hardware"] = "LilyGo T-CAN485";
|
|
||||||
#endif // HW_LILYGO
|
|
||||||
#ifdef HW_STARK
|
|
||||||
doc["hardware"] = "Stark CMR Module";
|
|
||||||
#endif // HW_STARK
|
|
||||||
#ifdef HW_3LB
|
|
||||||
doc["hardware"] = "3LB board";
|
|
||||||
#endif // HW_3LB
|
|
||||||
#ifdef HW_DEVKIT
|
|
||||||
doc["hardware"] = "ESP32 DevKit V1";
|
|
||||||
#endif // HW_DEVKIT
|
|
||||||
|
|
||||||
|
doc["hardware"] = esp32hal->name();
|
||||||
doc["firmware"] = String(version_number);
|
doc["firmware"] = String(version_number);
|
||||||
serializeJson(doc, content);
|
serializeJson(doc, content);
|
||||||
return content;
|
return content;
|
||||||
|
@ -977,7 +808,7 @@ String processor(const String& var) {
|
||||||
content += "</style>";
|
content += "</style>";
|
||||||
|
|
||||||
// Compact header
|
// Compact header
|
||||||
content += "<h2>" + String(ssidAP) + "</h2>";
|
content += "<h2>Battery Emulator</h2>";
|
||||||
|
|
||||||
// Start content block
|
// Start content block
|
||||||
content += "<div style='background-color: #303E47; padding: 10px; margin-bottom: 10px; border-radius: 50px'>";
|
content += "<div style='background-color: #303E47; padding: 10px; margin-bottom: 10px; border-radius: 50px'>";
|
||||||
|
@ -1037,7 +868,7 @@ String processor(const String& var) {
|
||||||
// Display which components are used
|
// Display which components are used
|
||||||
if (inverter) {
|
if (inverter) {
|
||||||
content += "<h4 style='color: white;'>Inverter protocol: ";
|
content += "<h4 style='color: white;'>Inverter protocol: ";
|
||||||
content += datalayer.system.info.inverter_protocol;
|
content += inverter->name();
|
||||||
content += " ";
|
content += " ";
|
||||||
content += datalayer.system.info.inverter_brand;
|
content += datalayer.system.info.inverter_brand;
|
||||||
content += "</h4>";
|
content += "</h4>";
|
||||||
|
@ -1291,9 +1122,11 @@ String processor(const String& var) {
|
||||||
content += " Cont. Pos.: ";
|
content += " Cont. Pos.: ";
|
||||||
content += "<span style='color: red;'>✕</span>";
|
content += "<span style='color: red;'>✕</span>";
|
||||||
}
|
}
|
||||||
} else { // No PWM_CONTACTOR_CONTROL , we can read the pin and see feedback. Helpful if channel overloaded
|
} else if (
|
||||||
|
esp32hal->SECOND_BATTERY_CONTACTORS_PIN() !=
|
||||||
|
GPIO_NUM_NC) { // No PWM_CONTACTOR_CONTROL , we can read the pin and see feedback. Helpful if channel overloaded
|
||||||
content += "<h4>Cont. Neg.: ";
|
content += "<h4>Cont. Neg.: ";
|
||||||
if (digitalRead(SECOND_BATTERY_CONTACTORS_PIN) == HIGH) {
|
if (digitalRead(esp32hal->SECOND_BATTERY_CONTACTORS_PIN()) == HIGH) {
|
||||||
content += "<span style='color: green;'>✓</span>";
|
content += "<span style='color: green;'>✓</span>";
|
||||||
} else {
|
} else {
|
||||||
content += "<span style='color: red;'>✕</span>";
|
content += "<span style='color: red;'>✕</span>";
|
||||||
|
@ -1532,7 +1365,7 @@ String processor(const String& var) {
|
||||||
content += "<button onclick='Cellmon()'>Cellmonitor</button> ";
|
content += "<button onclick='Cellmon()'>Cellmonitor</button> ";
|
||||||
content += "<button onclick='Events()'>Events</button> ";
|
content += "<button onclick='Events()'>Events</button> ";
|
||||||
content += "<button onclick='askReboot()'>Reboot Emulator</button>";
|
content += "<button onclick='askReboot()'>Reboot Emulator</button>";
|
||||||
if (WEBSERVER_AUTH_REQUIRED)
|
if (webserver_auth)
|
||||||
content += "<button onclick='logout()'>Logout</button>";
|
content += "<button onclick='logout()'>Logout</button>";
|
||||||
if (!datalayer.system.settings.equipment_stop_active)
|
if (!datalayer.system.settings.equipment_stop_active)
|
||||||
content +=
|
content +=
|
||||||
|
@ -1558,16 +1391,7 @@ String processor(const String& var) {
|
||||||
content += "function CANreplay() { window.location.href = '/canreplay'; }";
|
content += "function CANreplay() { window.location.href = '/canreplay'; }";
|
||||||
content += "function Log() { window.location.href = '/log'; }";
|
content += "function Log() { window.location.href = '/log'; }";
|
||||||
content += "function Events() { window.location.href = '/events'; }";
|
content += "function Events() { window.location.href = '/events'; }";
|
||||||
content +=
|
if (webserver_auth) {
|
||||||
"function askReboot() { if (window.confirm('Are you sure you want to reboot the emulator? NOTE: If "
|
|
||||||
"emulator is handling contactors, they will open during reboot!')) { "
|
|
||||||
"reboot(); } }";
|
|
||||||
content += "function reboot() {";
|
|
||||||
content += " var xhr = new XMLHttpRequest();";
|
|
||||||
content += " xhr.open('GET', '/reboot', true);";
|
|
||||||
content += " xhr.send();";
|
|
||||||
content += "}";
|
|
||||||
if (WEBSERVER_AUTH_REQUIRED) {
|
|
||||||
content += "function logout() {";
|
content += "function logout() {";
|
||||||
content += " var xhr = new XMLHttpRequest();";
|
content += " var xhr = new XMLHttpRequest();";
|
||||||
content += " xhr.open('GET', '/logout', true);";
|
content += " xhr.open('GET', '/logout', true);";
|
||||||
|
@ -1579,7 +1403,7 @@ String processor(const String& var) {
|
||||||
content +=
|
content +=
|
||||||
"var xhr=new "
|
"var xhr=new "
|
||||||
"XMLHttpRequest();xhr.onload=function() { "
|
"XMLHttpRequest();xhr.onload=function() { "
|
||||||
"window.location.reload();};xhr.open('GET','/pause?p='+pause,true);xhr.send();";
|
"window.location.reload();};xhr.open('GET','/pause?value='+pause,true);xhr.send();";
|
||||||
content += "}";
|
content += "}";
|
||||||
content += "function estop(stop){";
|
content += "function estop(stop){";
|
||||||
content +=
|
content +=
|
||||||
|
|
|
@ -9,14 +9,10 @@
|
||||||
#include "../../lib/ayushsharma82-ElegantOTA/src/ElegantOTA.h"
|
#include "../../lib/ayushsharma82-ElegantOTA/src/ElegantOTA.h"
|
||||||
#include "../../lib/mathieucarbou-AsyncTCPSock/src/AsyncTCP.h"
|
#include "../../lib/mathieucarbou-AsyncTCPSock/src/AsyncTCP.h"
|
||||||
|
|
||||||
|
extern bool webserver_enabled;
|
||||||
|
|
||||||
extern const char* version_number; // The current software version, shown on webserver
|
extern const char* version_number; // The current software version, shown on webserver
|
||||||
|
|
||||||
#include <string>
|
|
||||||
extern const char* http_username;
|
|
||||||
extern const char* http_password;
|
|
||||||
|
|
||||||
extern const char* ssidAP;
|
|
||||||
|
|
||||||
// Common charger parameters
|
// Common charger parameters
|
||||||
extern float charger_stat_HVcur;
|
extern float charger_stat_HVcur;
|
||||||
extern float charger_stat_HVvol;
|
extern float charger_stat_HVvol;
|
||||||
|
|
|
@ -1,7 +1,43 @@
|
||||||
#include "wifi.h"
|
#include "wifi.h"
|
||||||
|
#include <ESPmDNS.h>
|
||||||
#include "../../include.h"
|
#include "../../include.h"
|
||||||
#include "../utils/events.h"
|
#include "../utils/events.h"
|
||||||
|
|
||||||
|
#if defined(WIFI) || defined(WEBSERVER)
|
||||||
|
const bool wifi_enabled_default = true;
|
||||||
|
#else
|
||||||
|
const bool wifi_enabled_default = false;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
bool wifi_enabled = wifi_enabled_default;
|
||||||
|
|
||||||
|
#ifdef COMMON_IMAGE
|
||||||
|
const bool wifiap_enabled_default = true;
|
||||||
|
#else
|
||||||
|
#ifdef WIFIAP
|
||||||
|
const bool wifiap_enabled_default = true;
|
||||||
|
#else
|
||||||
|
const bool wifiap_enabled_default = false;
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
bool wifiap_enabled = wifiap_enabled_default;
|
||||||
|
|
||||||
|
#ifdef MDNSRESPONDER
|
||||||
|
const bool mdns_enabled_default = true;
|
||||||
|
#else
|
||||||
|
const bool mdns_enabled_default = false;
|
||||||
|
#endif
|
||||||
|
bool mdns_enabled = mdns_enabled_default;
|
||||||
|
|
||||||
|
#ifdef CUSTOM_HOSTNAME
|
||||||
|
std::string custom_hostname = CUSTOM_HOSTNAME;
|
||||||
|
#else
|
||||||
|
std::string custom_hostname;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
std::string ssidAP;
|
||||||
|
|
||||||
// Configuration Parameters
|
// Configuration Parameters
|
||||||
static const uint16_t WIFI_CHECK_INTERVAL = 2000; // 1 seconds normal check interval when last connected
|
static const uint16_t WIFI_CHECK_INTERVAL = 2000; // 1 seconds normal check interval when last connected
|
||||||
static const uint16_t STEP_WIFI_CHECK_INTERVAL = 2000; // 3 seconds wait step increase in checks for normal reconnects
|
static const uint16_t STEP_WIFI_CHECK_INTERVAL = 2000; // 3 seconds wait step increase in checks for normal reconnects
|
||||||
|
@ -27,17 +63,19 @@ static uint16_t current_check_interval = WIFI_CHECK_INTERVAL;
|
||||||
static bool connected_once = false;
|
static bool connected_once = false;
|
||||||
|
|
||||||
void init_WiFi() {
|
void init_WiFi() {
|
||||||
|
DEBUG_PRINTF("init_Wifi enabled=%d, apå=%d, ssid=%s, password=%s\n", wifi_enabled, wifiap_enabled, ssid.c_str(),
|
||||||
|
password.c_str());
|
||||||
|
|
||||||
#ifdef CUSTOM_HOSTNAME
|
if (!custom_hostname.empty()) {
|
||||||
WiFi.setHostname(CUSTOM_HOSTNAME); // Set custom hostname if defined in USER_SETTINGS.h
|
WiFi.setHostname(custom_hostname.c_str());
|
||||||
#endif
|
}
|
||||||
|
|
||||||
#ifdef WIFIAP
|
if (wifiap_enabled) {
|
||||||
WiFi.mode(WIFI_AP_STA); // Simultaneous WiFi AP and Router connection
|
WiFi.mode(WIFI_AP_STA); // Simultaneous WiFi AP and Router connection
|
||||||
init_WiFi_AP();
|
init_WiFi_AP();
|
||||||
#else
|
} else if (wifi_enabled) {
|
||||||
WiFi.mode(WIFI_STA); // Only Router connection
|
WiFi.mode(WIFI_STA); // Only Router connection
|
||||||
#endif // WIFIAP
|
}
|
||||||
|
|
||||||
// Set WiFi to auto reconnect
|
// Set WiFi to auto reconnect
|
||||||
WiFi.setAutoReconnect(true);
|
WiFi.setAutoReconnect(true);
|
||||||
|
@ -47,17 +85,26 @@ void init_WiFi() {
|
||||||
WiFi.config(local_IP, gateway, subnet);
|
WiFi.config(local_IP, gateway, subnet);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
DEBUG_PRINTF("init_Wifi set event handlers\n");
|
||||||
|
|
||||||
// Initialize Wi-Fi event handlers
|
// Initialize Wi-Fi event handlers
|
||||||
WiFi.onEvent(onWifiConnect, WiFiEvent_t::ARDUINO_EVENT_WIFI_STA_CONNECTED);
|
WiFi.onEvent(onWifiConnect, WiFiEvent_t::ARDUINO_EVENT_WIFI_STA_CONNECTED);
|
||||||
WiFi.onEvent(onWifiDisconnect, WiFiEvent_t::ARDUINO_EVENT_WIFI_STA_DISCONNECTED);
|
WiFi.onEvent(onWifiDisconnect, WiFiEvent_t::ARDUINO_EVENT_WIFI_STA_DISCONNECTED);
|
||||||
WiFi.onEvent(onWifiGotIP, WiFiEvent_t::ARDUINO_EVENT_WIFI_STA_GOT_IP);
|
WiFi.onEvent(onWifiGotIP, WiFiEvent_t::ARDUINO_EVENT_WIFI_STA_GOT_IP);
|
||||||
|
|
||||||
// Start Wi-Fi connection
|
// Start Wi-Fi connection
|
||||||
|
DEBUG_PRINTF("start Wifi\n");
|
||||||
connectToWiFi();
|
connectToWiFi();
|
||||||
|
|
||||||
|
DEBUG_PRINTF("init_Wifi complete\n");
|
||||||
}
|
}
|
||||||
|
|
||||||
// Task to monitor Wi-Fi status and handle reconnections
|
// Task to monitor Wi-Fi status and handle reconnections
|
||||||
void wifi_monitor() {
|
void wifi_monitor() {
|
||||||
|
if (ssid.empty() || password.empty()) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
unsigned long currentMillis = millis();
|
unsigned long currentMillis = millis();
|
||||||
|
|
||||||
// Check if it's time to monitor the Wi-Fi status
|
// Check if it's time to monitor the Wi-Fi status
|
||||||
|
@ -104,6 +151,11 @@ void wifi_monitor() {
|
||||||
#ifdef DEBUG_LOG
|
#ifdef DEBUG_LOG
|
||||||
logging.println("No previous OK connection, force a full connection attempt...");
|
logging.println("No previous OK connection, force a full connection attempt...");
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
wifiap_enabled = true;
|
||||||
|
WiFi.mode(WIFI_AP_STA);
|
||||||
|
init_WiFi_AP();
|
||||||
|
|
||||||
FullReconnectToWiFi();
|
FullReconnectToWiFi();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -125,11 +177,18 @@ void FullReconnectToWiFi() {
|
||||||
|
|
||||||
// Function to handle Wi-Fi connection
|
// Function to handle Wi-Fi connection
|
||||||
void connectToWiFi() {
|
void connectToWiFi() {
|
||||||
|
if (ssid.empty() || password.empty()) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
if (WiFi.status() != WL_CONNECTED) {
|
if (WiFi.status() != WL_CONNECTED) {
|
||||||
lastReconnectAttempt = millis(); // Reset the reconnect attempt timer
|
lastReconnectAttempt = millis(); // Reset the reconnect attempt timer
|
||||||
#ifdef DEBUG_LOG
|
#ifdef DEBUG_LOG
|
||||||
logging.println("Connecting to Wi-Fi...");
|
logging.println("Connecting to Wi-Fi...");
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
DEBUG_PRINTF("Connecting to Wi-Fi SSID: %s, password: %s, Channel: %d\n", ssid.c_str(), password.c_str(),
|
||||||
|
wifi_channel);
|
||||||
WiFi.begin(ssid.c_str(), password.c_str(), wifi_channel);
|
WiFi.begin(ssid.c_str(), password.c_str(), wifi_channel);
|
||||||
} else {
|
} else {
|
||||||
#ifdef DEBUG_LOG
|
#ifdef DEBUG_LOG
|
||||||
|
@ -143,12 +202,8 @@ void onWifiConnect(WiFiEvent_t event, WiFiEventInfo_t info) {
|
||||||
clear_event(EVENT_WIFI_DISCONNECT);
|
clear_event(EVENT_WIFI_DISCONNECT);
|
||||||
set_event(EVENT_WIFI_CONNECT, 0);
|
set_event(EVENT_WIFI_CONNECT, 0);
|
||||||
connected_once = true;
|
connected_once = true;
|
||||||
#ifdef DEBUG_LOG
|
DEBUG_PRINTF("Wi-Fi connected. RSSI: %d dBm, IP address: %s, SSID: %s\n", -WiFi.RSSI(),
|
||||||
logging.print("Wi-Fi connected. RSSI: ");
|
WiFi.localIP().toString().c_str(), WiFi.SSID().c_str());
|
||||||
logging.print(-WiFi.RSSI());
|
|
||||||
logging.print(" dBm, IP address: ");
|
|
||||||
logging.println(WiFi.localIP().toString());
|
|
||||||
#endif
|
|
||||||
hasConnectedBefore = true; // Mark as successfully connected at least once
|
hasConnectedBefore = true; // Mark as successfully connected at least once
|
||||||
reconnectAttempts = 0; // Reset the attempt counter
|
reconnectAttempts = 0; // Reset the attempt counter
|
||||||
current_full_reconnect_interval = INIT_WIFI_FULL_RECONNECT_INTERVAL; // Reset the full reconnect interval
|
current_full_reconnect_interval = INIT_WIFI_FULL_RECONNECT_INTERVAL; // Reset the full reconnect interval
|
||||||
|
@ -169,8 +224,10 @@ void onWifiGotIP(WiFiEvent_t event, WiFiEventInfo_t info) {
|
||||||
|
|
||||||
// Event handler for Wi-Fi disconnection
|
// Event handler for Wi-Fi disconnection
|
||||||
void onWifiDisconnect(WiFiEvent_t event, WiFiEventInfo_t info) {
|
void onWifiDisconnect(WiFiEvent_t event, WiFiEventInfo_t info) {
|
||||||
if (connected_once)
|
|
||||||
|
if (connected_once) {
|
||||||
set_event(EVENT_WIFI_DISCONNECT, 0);
|
set_event(EVENT_WIFI_DISCONNECT, 0);
|
||||||
|
}
|
||||||
#ifdef DEBUG_LOG
|
#ifdef DEBUG_LOG
|
||||||
logging.println("Wi-Fi disconnected.");
|
logging.println("Wi-Fi disconnected.");
|
||||||
#endif
|
#endif
|
||||||
|
@ -179,16 +236,16 @@ void onWifiDisconnect(WiFiEvent_t event, WiFiEventInfo_t info) {
|
||||||
//normal reconnect retry start at first 2 seconds
|
//normal reconnect retry start at first 2 seconds
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef MDNSRESPONDER
|
|
||||||
// Initialise mDNS
|
// Initialise mDNS
|
||||||
void init_mDNS() {
|
void init_mDNS() {
|
||||||
// Calulate the host name using the last two chars from the MAC address so each one is likely unique on a network.
|
// Calulate the host name using the last two chars from the MAC address so each one is likely unique on a network.
|
||||||
// e.g batteryemulator8C.local where the mac address is 08:F9:E0:D1:06:8C
|
// e.g batteryemulator8C.local where the mac address is 08:F9:E0:D1:06:8C
|
||||||
String mac = WiFi.macAddress();
|
String mac = WiFi.macAddress();
|
||||||
String mdnsHost = "batteryemulator" + mac.substring(mac.length() - 2);
|
String mdnsHost = "batteryemulator" + mac.substring(mac.length() - 2);
|
||||||
#ifdef CUSTOM_HOSTNAME // If CUSTOM_HOSTNAME is defined, use the same hostname also for mDNS
|
|
||||||
mdnsHost = CUSTOM_HOSTNAME;
|
if (!custom_hostname.empty()) {
|
||||||
#endif
|
mdnsHost = String(custom_hostname.c_str());
|
||||||
|
}
|
||||||
|
|
||||||
// Initialize mDNS .local resolution
|
// Initialize mDNS .local resolution
|
||||||
if (!MDNS.begin(mdnsHost)) {
|
if (!MDNS.begin(mdnsHost)) {
|
||||||
|
@ -200,20 +257,15 @@ void init_mDNS() {
|
||||||
MDNS.addService(mdnsHost, "tcp", 80);
|
MDNS.addService(mdnsHost, "tcp", 80);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif // MDNSRESPONDER
|
|
||||||
|
|
||||||
#ifdef WIFIAP
|
|
||||||
void init_WiFi_AP() {
|
void init_WiFi_AP() {
|
||||||
#ifdef DEBUG_LOG
|
ssidAP = std::string("BatteryEmulator") + WiFi.macAddress().c_str();
|
||||||
logging.println("Creating Access Point: " + String(ssidAP));
|
|
||||||
logging.println("With password: " + String(passwordAP));
|
DEBUG_PRINTF("Creating Access Point: %s\n", ssidAP.c_str());
|
||||||
#endif
|
DEBUG_PRINTF("With password: %s\n", passwordAP.c_str());
|
||||||
WiFi.softAP(ssidAP, passwordAP);
|
|
||||||
|
WiFi.softAP(ssidAP.c_str(), passwordAP.c_str());
|
||||||
IPAddress IP = WiFi.softAPIP();
|
IPAddress IP = WiFi.softAPIP();
|
||||||
#ifdef DEBUG_LOG
|
|
||||||
logging.println("Access Point created.");
|
DEBUG_PRINTF("Access Point created.\nIP address: %s\n", IP.toString().c_str());
|
||||||
logging.print("IP address: ");
|
|
||||||
logging.println(IP.toString());
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
#endif // WIFIAP
|
|
||||||
|
|
|
@ -5,15 +5,12 @@
|
||||||
#include <string>
|
#include <string>
|
||||||
#include "../../include.h"
|
#include "../../include.h"
|
||||||
|
|
||||||
#ifdef MDNSRESPONDER
|
|
||||||
#include <ESPmDNS.h>
|
|
||||||
#endif // MDNSRESONDER
|
|
||||||
|
|
||||||
extern std::string ssid;
|
extern std::string ssid;
|
||||||
extern std::string password;
|
extern std::string password;
|
||||||
extern const uint8_t wifi_channel;
|
extern const uint8_t wifi_channel;
|
||||||
extern const char* ssidAP;
|
extern std::string ssidAP;
|
||||||
extern const char* passwordAP;
|
extern std::string passwordAP;
|
||||||
|
extern std::string custom_hostname;
|
||||||
|
|
||||||
void init_WiFi();
|
void init_WiFi();
|
||||||
void wifi_monitor();
|
void wifi_monitor();
|
||||||
|
@ -23,13 +20,13 @@ void onWifiConnect(WiFiEvent_t event, WiFiEventInfo_t info);
|
||||||
void onWifiDisconnect(WiFiEvent_t event, WiFiEventInfo_t info);
|
void onWifiDisconnect(WiFiEvent_t event, WiFiEventInfo_t info);
|
||||||
void onWifiGotIP(WiFiEvent_t event, WiFiEventInfo_t info);
|
void onWifiGotIP(WiFiEvent_t event, WiFiEventInfo_t info);
|
||||||
|
|
||||||
#ifdef WIFIAP
|
|
||||||
void init_WiFi_AP();
|
void init_WiFi_AP();
|
||||||
#endif // WIFIAP
|
|
||||||
|
|
||||||
#ifdef MDNSRESPONDER
|
|
||||||
// Initialise mDNS
|
// Initialise mDNS
|
||||||
void init_mDNS();
|
void init_mDNS();
|
||||||
#endif // MDNSRESPONDER
|
|
||||||
|
extern bool wifi_enabled;
|
||||||
|
extern bool wifiap_enabled;
|
||||||
|
extern bool mdns_enabled;
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -19,17 +19,10 @@
|
||||||
|
|
||||||
/* - ERROR CHECKS BELOW, DON'T TOUCH - */
|
/* - ERROR CHECKS BELOW, DON'T TOUCH - */
|
||||||
|
|
||||||
#if !defined(HW_CONFIGURED)
|
#if !defined(HW_LILYGO) && !defined(HW_STARK) && !defined(HW_3LB) && !defined(HW_DEVKIT)
|
||||||
#error You must select a target hardware in the USER_SETTINGS.h file!
|
#error You must select a target hardware in the USER_SETTINGS.h file!
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_CANFD_INTERFACE_AS_CLASSIC_CAN
|
|
||||||
#if !defined(CANFD_ADDON)
|
|
||||||
// Check that user did not try to use classic CAN over FD, without FD component
|
|
||||||
#error PLEASE ENABLE CANFD_ADDON TO USE CLASSIC CAN OVER CANFD INTERFACE
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef HW_LILYGO
|
#ifdef HW_LILYGO
|
||||||
#if defined(PERIODIC_BMS_RESET) || defined(REMOTE_BMS_RESET)
|
#if defined(PERIODIC_BMS_RESET) || defined(REMOTE_BMS_RESET)
|
||||||
#if defined(CAN_ADDON) || defined(CANFD_ADDON) || defined(CHADEMO_BATTERY)
|
#if defined(CAN_ADDON) || defined(CANFD_ADDON) || defined(CHADEMO_BATTERY)
|
||||||
|
|
|
@ -169,8 +169,3 @@ void AforeCanInverter::transmit_can(unsigned long currentMillis) {
|
||||||
time_to_send_info = false;
|
time_to_send_info = false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void AforeCanInverter::setup(void) { // Performs one time setup at startup over CAN bus
|
|
||||||
strncpy(datalayer.system.info.inverter_protocol, Name, 63);
|
|
||||||
datalayer.system.info.inverter_protocol[63] = '\0';
|
|
||||||
}
|
|
||||||
|
|
|
@ -10,7 +10,7 @@
|
||||||
|
|
||||||
class AforeCanInverter : public CanInverterProtocol {
|
class AforeCanInverter : public CanInverterProtocol {
|
||||||
public:
|
public:
|
||||||
void setup();
|
const char* name() override { return Name; }
|
||||||
void transmit_can(unsigned long currentMillis);
|
void transmit_can(unsigned long currentMillis);
|
||||||
void map_can_frame_to_variable(CAN_frame rx_frame);
|
void map_can_frame_to_variable(CAN_frame rx_frame);
|
||||||
void update_values();
|
void update_values();
|
||||||
|
|
|
@ -169,8 +169,3 @@ void BydCanInverter::send_initial_data() {
|
||||||
transmit_can_frame(&BYD_3D0_2, can_config.inverter);
|
transmit_can_frame(&BYD_3D0_2, can_config.inverter);
|
||||||
transmit_can_frame(&BYD_3D0_3, can_config.inverter);
|
transmit_can_frame(&BYD_3D0_3, can_config.inverter);
|
||||||
}
|
}
|
||||||
|
|
||||||
void BydCanInverter::setup(void) { // Performs one time setup at startup over CAN bus
|
|
||||||
strncpy(datalayer.system.info.inverter_protocol, Name, 63);
|
|
||||||
datalayer.system.info.inverter_protocol[63] = '\0';
|
|
||||||
}
|
|
||||||
|
|
|
@ -10,7 +10,7 @@
|
||||||
|
|
||||||
class BydCanInverter : public CanInverterProtocol {
|
class BydCanInverter : public CanInverterProtocol {
|
||||||
public:
|
public:
|
||||||
void setup();
|
const char* name() override { return Name; }
|
||||||
void transmit_can(unsigned long currentMillis);
|
void transmit_can(unsigned long currentMillis);
|
||||||
void map_can_frame_to_variable(CAN_frame rx_frame);
|
void map_can_frame_to_variable(CAN_frame rx_frame);
|
||||||
void update_values();
|
void update_values();
|
||||||
|
|
|
@ -145,17 +145,21 @@ void BydModbusInverter::verify_inverter_modbus() {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void BydModbusInverter::setup(void) { // Performs one time setup at startup over CAN bus
|
bool BydModbusInverter::setup(void) { // Performs one time setup at startup over CAN bus
|
||||||
strncpy(datalayer.system.info.inverter_protocol, Name, 63);
|
|
||||||
datalayer.system.info.inverter_protocol[63] = '\0';
|
|
||||||
|
|
||||||
// Init Static data to the RTU Modbus
|
// Init Static data to the RTU Modbus
|
||||||
handle_static_data();
|
handle_static_data();
|
||||||
|
|
||||||
// Init Serial2 connected to the RTU Modbus
|
// Init Serial2 connected to the RTU Modbus
|
||||||
RTUutils::prepareHardwareSerial(Serial2);
|
RTUutils::prepareHardwareSerial(Serial2);
|
||||||
|
|
||||||
Serial2.begin(9600, SERIAL_8N1, RS485_RX_PIN, RS485_TX_PIN);
|
auto rx_pin = esp32hal->RS485_RX_PIN();
|
||||||
|
auto tx_pin = esp32hal->RS485_TX_PIN();
|
||||||
|
|
||||||
|
if (!esp32hal->alloc_pins(Name, rx_pin, tx_pin)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
Serial2.begin(9600, SERIAL_8N1, rx_pin, tx_pin);
|
||||||
// Register served function code worker for server
|
// Register served function code worker for server
|
||||||
MBserver.registerWorker(MBTCP_ID, READ_HOLD_REGISTER, &FC03);
|
MBserver.registerWorker(MBTCP_ID, READ_HOLD_REGISTER, &FC03);
|
||||||
MBserver.registerWorker(MBTCP_ID, WRITE_HOLD_REGISTER, &FC06);
|
MBserver.registerWorker(MBTCP_ID, WRITE_HOLD_REGISTER, &FC06);
|
||||||
|
@ -163,5 +167,7 @@ void BydModbusInverter::setup(void) { // Performs one time setup at startup ove
|
||||||
MBserver.registerWorker(MBTCP_ID, R_W_MULT_REGISTERS, &FC23);
|
MBserver.registerWorker(MBTCP_ID, R_W_MULT_REGISTERS, &FC23);
|
||||||
|
|
||||||
// Start ModbusRTU background task
|
// Start ModbusRTU background task
|
||||||
MBserver.begin(Serial2, MODBUS_CORE);
|
MBserver.begin(Serial2, esp32hal->MODBUS_CORE());
|
||||||
|
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
|
@ -10,7 +10,8 @@
|
||||||
|
|
||||||
class BydModbusInverter : public ModbusInverterProtocol {
|
class BydModbusInverter : public ModbusInverterProtocol {
|
||||||
public:
|
public:
|
||||||
void setup();
|
const char* name() override { return Name; }
|
||||||
|
bool setup() override;
|
||||||
void update_values();
|
void update_values();
|
||||||
static constexpr const char* Name = "BYD 11kWh HVM battery over Modbus RTU";
|
static constexpr const char* Name = "BYD 11kWh HVM battery over Modbus RTU";
|
||||||
|
|
||||||
|
|
|
@ -4,6 +4,7 @@
|
||||||
#include "InverterProtocol.h"
|
#include "InverterProtocol.h"
|
||||||
|
|
||||||
#include "src/communication/can/CanReceiver.h"
|
#include "src/communication/can/CanReceiver.h"
|
||||||
|
#include "src/communication/can/comm_can.h"
|
||||||
#include "src/devboard/utils/types.h"
|
#include "src/devboard/utils/types.h"
|
||||||
|
|
||||||
class CanInverterProtocol : public InverterProtocol, Transmitter, CanReceiver {
|
class CanInverterProtocol : public InverterProtocol, Transmitter, CanReceiver {
|
||||||
|
|
|
@ -365,8 +365,3 @@ void FerroampCanInverter::send_system_data() { //System equipment information
|
||||||
transmit_can_frame(&PYLON_4291, can_config.inverter);
|
transmit_can_frame(&PYLON_4291, can_config.inverter);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
void FerroampCanInverter::setup(void) { // Performs one time setup at startup over CAN bus
|
|
||||||
strncpy(datalayer.system.info.inverter_protocol, Name, 63);
|
|
||||||
datalayer.system.info.inverter_protocol[63] = '\0';
|
|
||||||
}
|
|
||||||
|
|
|
@ -10,7 +10,7 @@
|
||||||
|
|
||||||
class FerroampCanInverter : public CanInverterProtocol {
|
class FerroampCanInverter : public CanInverterProtocol {
|
||||||
public:
|
public:
|
||||||
void setup();
|
const char* name() override { return Name; }
|
||||||
void update_values();
|
void update_values();
|
||||||
void transmit_can(unsigned long currentMillis);
|
void transmit_can(unsigned long currentMillis);
|
||||||
void map_can_frame_to_variable(CAN_frame rx_frame);
|
void map_can_frame_to_variable(CAN_frame rx_frame);
|
||||||
|
|
|
@ -561,7 +561,3 @@ void FoxessCanInverter::map_can_frame_to_variable(CAN_frame rx_frame) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
void FoxessCanInverter::setup(void) { // Performs one time setup at startup over CAN bus
|
|
||||||
strncpy(datalayer.system.info.inverter_protocol, Name, 63);
|
|
||||||
datalayer.system.info.inverter_protocol[63] = '\0';
|
|
||||||
}
|
|
||||||
|
|
|
@ -10,7 +10,7 @@
|
||||||
|
|
||||||
class FoxessCanInverter : public CanInverterProtocol {
|
class FoxessCanInverter : public CanInverterProtocol {
|
||||||
public:
|
public:
|
||||||
void setup();
|
const char* name() override { return Name; }
|
||||||
void update_values();
|
void update_values();
|
||||||
void transmit_can(unsigned long currentMillis);
|
void transmit_can(unsigned long currentMillis);
|
||||||
void map_can_frame_to_variable(CAN_frame rx_frame);
|
void map_can_frame_to_variable(CAN_frame rx_frame);
|
||||||
|
|
|
@ -449,8 +449,3 @@ void GrowattHvInverter::transmit_can(unsigned long currentMillis) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void GrowattHvInverter::setup(void) { // Performs one time setup at startup over CAN bus
|
|
||||||
strncpy(datalayer.system.info.inverter_protocol, Name, 63);
|
|
||||||
datalayer.system.info.inverter_protocol[63] = '\0';
|
|
||||||
}
|
|
||||||
|
|
|
@ -10,7 +10,7 @@
|
||||||
|
|
||||||
class GrowattHvInverter : public CanInverterProtocol {
|
class GrowattHvInverter : public CanInverterProtocol {
|
||||||
public:
|
public:
|
||||||
void setup();
|
const char* name() override { return Name; }
|
||||||
void update_values();
|
void update_values();
|
||||||
void transmit_can(unsigned long currentMillis);
|
void transmit_can(unsigned long currentMillis);
|
||||||
void map_can_frame_to_variable(CAN_frame rx_frame);
|
void map_can_frame_to_variable(CAN_frame rx_frame);
|
||||||
|
|
|
@ -202,8 +202,3 @@ void GrowattLvInverter::map_can_frame_to_variable(CAN_frame rx_frame) {
|
||||||
void GrowattLvInverter::transmit_can(unsigned long currentMillis) {
|
void GrowattLvInverter::transmit_can(unsigned long currentMillis) {
|
||||||
// No periodic sending for this battery type. Data is sent when inverter requests it
|
// No periodic sending for this battery type. Data is sent when inverter requests it
|
||||||
}
|
}
|
||||||
|
|
||||||
void GrowattLvInverter::setup(void) { // Performs one time setup at startup over CAN bus
|
|
||||||
strncpy(datalayer.system.info.inverter_protocol, Name, 63);
|
|
||||||
datalayer.system.info.inverter_protocol[63] = '\0';
|
|
||||||
}
|
|
||||||
|
|
|
@ -10,7 +10,7 @@
|
||||||
|
|
||||||
class GrowattLvInverter : public CanInverterProtocol {
|
class GrowattLvInverter : public CanInverterProtocol {
|
||||||
public:
|
public:
|
||||||
void setup();
|
const char* name() override { return Name; }
|
||||||
void update_values();
|
void update_values();
|
||||||
void transmit_can(unsigned long currentMillis);
|
void transmit_can(unsigned long currentMillis);
|
||||||
void map_can_frame_to_variable(CAN_frame rx_frame);
|
void map_can_frame_to_variable(CAN_frame rx_frame);
|
||||||
|
|
|
@ -84,9 +84,9 @@ extern const char* name_for_inverter_type(InverterProtocolType type) {
|
||||||
#error "Compile time SELECTED_INVERTER_CLASS should not be defined with COMMON_IMAGE"
|
#error "Compile time SELECTED_INVERTER_CLASS should not be defined with COMMON_IMAGE"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
void setup_inverter() {
|
bool setup_inverter() {
|
||||||
if (inverter) {
|
if (inverter) {
|
||||||
return;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
switch (user_selected_inverter_protocol) {
|
switch (user_selected_inverter_protocol) {
|
||||||
|
@ -167,6 +167,7 @@ void setup_inverter() {
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case InverterProtocolType::None:
|
case InverterProtocolType::None:
|
||||||
|
return true;
|
||||||
case InverterProtocolType::Highest:
|
case InverterProtocolType::Highest:
|
||||||
default:
|
default:
|
||||||
inverter = nullptr; // Or handle as error
|
inverter = nullptr; // Or handle as error
|
||||||
|
@ -174,23 +175,29 @@ void setup_inverter() {
|
||||||
}
|
}
|
||||||
|
|
||||||
if (inverter) {
|
if (inverter) {
|
||||||
inverter->setup();
|
return inverter->setup();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
#else
|
#else
|
||||||
void setup_inverter() {
|
bool setup_inverter() {
|
||||||
if (inverter) {
|
if (inverter) {
|
||||||
// The inverter is setup only once.
|
// The inverter is setup only once.
|
||||||
return;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef SELECTED_INVERTER_CLASS
|
#ifdef SELECTED_INVERTER_CLASS
|
||||||
inverter = new SELECTED_INVERTER_CLASS();
|
inverter = new SELECTED_INVERTER_CLASS();
|
||||||
|
|
||||||
if (inverter) {
|
if (inverter) {
|
||||||
inverter->setup();
|
return inverter->setup();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
return false;
|
||||||
|
#else
|
||||||
|
return true;
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -32,6 +32,6 @@ extern InverterProtocol* inverter;
|
||||||
#include "SUNGROW-CAN.h"
|
#include "SUNGROW-CAN.h"
|
||||||
|
|
||||||
// Call to initialize the build-time selected inverter. Safe to call even though inverter was not selected.
|
// Call to initialize the build-time selected inverter. Safe to call even though inverter was not selected.
|
||||||
void setup_inverter();
|
bool setup_inverter();
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -35,7 +35,8 @@ enum class InverterInterfaceType { Can, Rs485, Modbus };
|
||||||
// The abstract base class for all inverter protocols
|
// The abstract base class for all inverter protocols
|
||||||
class InverterProtocol {
|
class InverterProtocol {
|
||||||
public:
|
public:
|
||||||
virtual void setup() = 0;
|
virtual const char* name() = 0;
|
||||||
|
virtual bool setup() { return true; }
|
||||||
virtual const char* interface_name() = 0;
|
virtual const char* interface_name() = 0;
|
||||||
virtual InverterInterfaceType interface_type() = 0;
|
virtual InverterInterfaceType interface_type() = 0;
|
||||||
|
|
||||||
|
@ -46,6 +47,8 @@ class InverterProtocol {
|
||||||
virtual bool controls_contactor() { return false; }
|
virtual bool controls_contactor() { return false; }
|
||||||
|
|
||||||
virtual bool allows_contactor_closing() { return false; }
|
virtual bool allows_contactor_closing() { return false; }
|
||||||
|
|
||||||
|
virtual bool supports_battery_id() { return false; }
|
||||||
};
|
};
|
||||||
|
|
||||||
extern InverterProtocol* inverter;
|
extern InverterProtocol* inverter;
|
||||||
|
|
|
@ -301,11 +301,18 @@ void KostalInverterProtocol::receive() // Runs as fast as possible to handle th
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void KostalInverterProtocol::setup(void) { // Performs one time setup at startup
|
bool KostalInverterProtocol::setup(void) { // Performs one time setup at startup
|
||||||
datalayer.system.status.inverter_allows_contactor_closing = false;
|
datalayer.system.status.inverter_allows_contactor_closing = false;
|
||||||
dbg_message("inverter_allows_contactor_closing -> false");
|
dbg_message("inverter_allows_contactor_closing -> false");
|
||||||
strncpy(datalayer.system.info.inverter_protocol, Name, 63);
|
|
||||||
datalayer.system.info.inverter_protocol[63] = '\0';
|
|
||||||
|
|
||||||
Serial2.begin(baud_rate(), SERIAL_8N1, RS485_RX_PIN, RS485_TX_PIN);
|
auto rx_pin = esp32hal->RS485_RX_PIN();
|
||||||
|
auto tx_pin = esp32hal->RS485_TX_PIN();
|
||||||
|
|
||||||
|
if (!esp32hal->alloc_pins(Name, rx_pin, tx_pin)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
Serial2.begin(baud_rate(), SERIAL_8N1, rx_pin, tx_pin);
|
||||||
|
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
|
@ -19,7 +19,8 @@
|
||||||
|
|
||||||
class KostalInverterProtocol : public Rs485InverterProtocol {
|
class KostalInverterProtocol : public Rs485InverterProtocol {
|
||||||
public:
|
public:
|
||||||
void setup();
|
const char* name() override { return Name; }
|
||||||
|
bool setup() override;
|
||||||
void receive();
|
void receive();
|
||||||
void update_values();
|
void update_values();
|
||||||
static constexpr const char* Name = "BYD battery via Kostal RS485";
|
static constexpr const char* Name = "BYD battery via Kostal RS485";
|
||||||
|
|
|
@ -352,8 +352,3 @@ void PylonInverter::send_system_data() { //System equipment information
|
||||||
transmit_can_frame(&PYLON_4291, can_config.inverter);
|
transmit_can_frame(&PYLON_4291, can_config.inverter);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
void PylonInverter::setup(void) { // Performs one time setup at startup over CAN bus
|
|
||||||
strncpy(datalayer.system.info.inverter_protocol, Name, 63);
|
|
||||||
datalayer.system.info.inverter_protocol[63] = '\0';
|
|
||||||
}
|
|
||||||
|
|
|
@ -10,7 +10,7 @@
|
||||||
|
|
||||||
class PylonInverter : public CanInverterProtocol {
|
class PylonInverter : public CanInverterProtocol {
|
||||||
public:
|
public:
|
||||||
void setup();
|
const char* name() override { return Name; }
|
||||||
void update_values();
|
void update_values();
|
||||||
void transmit_can(unsigned long currentMillis);
|
void transmit_can(unsigned long currentMillis);
|
||||||
void map_can_frame_to_variable(CAN_frame rx_frame);
|
void map_can_frame_to_variable(CAN_frame rx_frame);
|
||||||
|
|
|
@ -144,8 +144,3 @@ void PylonLvInverter::transmit_can(unsigned long currentMillis) {
|
||||||
transmit_can_frame(&PYLON_35E, can_config.inverter);
|
transmit_can_frame(&PYLON_35E, can_config.inverter);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void PylonLvInverter::setup(void) { // Performs one time setup at startup over CAN bus
|
|
||||||
strncpy(datalayer.system.info.inverter_protocol, Name, 63);
|
|
||||||
datalayer.system.info.inverter_protocol[63] = '\0';
|
|
||||||
}
|
|
||||||
|
|
|
@ -10,7 +10,7 @@
|
||||||
|
|
||||||
class PylonLvInverter : public CanInverterProtocol {
|
class PylonLvInverter : public CanInverterProtocol {
|
||||||
public:
|
public:
|
||||||
void setup();
|
const char* name() override { return Name; }
|
||||||
void update_values();
|
void update_values();
|
||||||
void transmit_can(unsigned long currentMillis);
|
void transmit_can(unsigned long currentMillis);
|
||||||
void map_can_frame_to_variable(CAN_frame rx_frame);
|
void map_can_frame_to_variable(CAN_frame rx_frame);
|
||||||
|
|
|
@ -225,8 +225,3 @@ void SchneiderInverter::transmit_can(unsigned long currentMillis) {
|
||||||
transmit_can_frame(&SE_333, can_config.inverter);
|
transmit_can_frame(&SE_333, can_config.inverter);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void SchneiderInverter::setup(void) { // Performs one time setup
|
|
||||||
strncpy(datalayer.system.info.inverter_protocol, Name, 63);
|
|
||||||
datalayer.system.info.inverter_protocol[63] = '\0';
|
|
||||||
}
|
|
||||||
|
|
|
@ -10,7 +10,7 @@
|
||||||
|
|
||||||
class SchneiderInverter : public CanInverterProtocol {
|
class SchneiderInverter : public CanInverterProtocol {
|
||||||
public:
|
public:
|
||||||
void setup();
|
const char* name() override { return Name; }
|
||||||
void update_values();
|
void update_values();
|
||||||
void transmit_can(unsigned long currentMillis);
|
void transmit_can(unsigned long currentMillis);
|
||||||
void map_can_frame_to_variable(CAN_frame rx_frame);
|
void map_can_frame_to_variable(CAN_frame rx_frame);
|
||||||
|
|
|
@ -69,16 +69,7 @@ void SmaBydHInverter::
|
||||||
SMA_158.data.u8[2] = 0x6A;
|
SMA_158.data.u8[2] = 0x6A;
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef INVERTER_CONTACTOR_ENABLE_LED_PIN
|
control_contactor_led();
|
||||||
// Inverter allows contactor closing
|
|
||||||
if (datalayer.system.status.inverter_allows_contactor_closing) {
|
|
||||||
digitalWrite(INVERTER_CONTACTOR_ENABLE_LED_PIN,
|
|
||||||
HIGH); // Turn on LED to indicate that SMA inverter allows contactor closing
|
|
||||||
} else {
|
|
||||||
digitalWrite(INVERTER_CONTACTOR_ENABLE_LED_PIN,
|
|
||||||
LOW); // Turn off LED to indicate that SMA inverter does not allow contactor closing
|
|
||||||
}
|
|
||||||
#endif // INVERTER_CONTACTOR_ENABLE_LED_PIN
|
|
||||||
|
|
||||||
// Check if Enable line is working. If we go too long without any input, raise an event
|
// Check if Enable line is working. If we go too long without any input, raise an event
|
||||||
if (!datalayer.system.status.inverter_allows_contactor_closing) {
|
if (!datalayer.system.status.inverter_allows_contactor_closing) {
|
||||||
|
@ -258,14 +249,3 @@ void SmaBydHInverter::transmit_can_init() {
|
||||||
transmit_can_frame(&SMA_518, can_config.inverter);
|
transmit_can_frame(&SMA_518, can_config.inverter);
|
||||||
transmit_can_frame(&SMA_4D8, can_config.inverter);
|
transmit_can_frame(&SMA_4D8, can_config.inverter);
|
||||||
}
|
}
|
||||||
|
|
||||||
void SmaBydHInverter::setup(void) { // Performs one time setup at startup over CAN bus
|
|
||||||
strncpy(datalayer.system.info.inverter_protocol, Name, 63);
|
|
||||||
datalayer.system.info.inverter_protocol[63] = '\0';
|
|
||||||
datalayer.system.status.inverter_allows_contactor_closing = false; // The inverter needs to allow first
|
|
||||||
pinMode(INVERTER_CONTACTOR_ENABLE_PIN, INPUT);
|
|
||||||
#ifdef INVERTER_CONTACTOR_ENABLE_LED_PIN
|
|
||||||
pinMode(INVERTER_CONTACTOR_ENABLE_LED_PIN, OUTPUT);
|
|
||||||
digitalWrite(INVERTER_CONTACTOR_ENABLE_LED_PIN, LOW); // Turn LED off, until inverter allows contactor closing
|
|
||||||
#endif // INVERTER_CONTACTOR_ENABLE_LED_PIN
|
|
||||||
}
|
|
||||||
|
|
|
@ -2,23 +2,22 @@
|
||||||
#define SMA_BYD_H_CAN_H
|
#define SMA_BYD_H_CAN_H
|
||||||
#include "../include.h"
|
#include "../include.h"
|
||||||
|
|
||||||
#include "CanInverterProtocol.h"
|
#include "SmaInverterBase.h"
|
||||||
#include "src/devboard/hal/hal.h"
|
#include "src/devboard/hal/hal.h"
|
||||||
|
|
||||||
#ifdef SMA_BYD_H_CAN
|
#ifdef SMA_BYD_H_CAN
|
||||||
#define SELECTED_INVERTER_CLASS SmaBydHInverter
|
#define SELECTED_INVERTER_CLASS SmaBydHInverter
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
class SmaBydHInverter : public CanInverterProtocol {
|
class SmaBydHInverter : public SmaInverterBase {
|
||||||
public:
|
public:
|
||||||
void setup();
|
const char* name() override { return Name; }
|
||||||
void update_values();
|
void update_values();
|
||||||
void transmit_can(unsigned long currentMillis);
|
void transmit_can(unsigned long currentMillis);
|
||||||
void map_can_frame_to_variable(CAN_frame rx_frame);
|
void map_can_frame_to_variable(CAN_frame rx_frame);
|
||||||
static constexpr const char* Name = "BYD over SMA CAN";
|
static constexpr const char* Name = "BYD over SMA CAN";
|
||||||
|
|
||||||
virtual bool controls_contactor() { return true; }
|
virtual bool controls_contactor() { return true; }
|
||||||
virtual bool allows_contactor_closing() { return digitalRead(INVERTER_CONTACTOR_ENABLE_PIN) == 1; }
|
|
||||||
|
|
||||||
private:
|
private:
|
||||||
static const int READY_STATE = 0x03;
|
static const int READY_STATE = 0x03;
|
||||||
|
|
|
@ -68,16 +68,7 @@ void SmaBydHvsInverter::
|
||||||
SMA_158.data.u8[2] = 0x6A;
|
SMA_158.data.u8[2] = 0x6A;
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef INVERTER_CONTACTOR_ENABLE_LED_PIN
|
control_contactor_led();
|
||||||
// Inverter allows contactor closing
|
|
||||||
if (datalayer.system.status.inverter_allows_contactor_closing) {
|
|
||||||
digitalWrite(INVERTER_CONTACTOR_ENABLE_LED_PIN,
|
|
||||||
HIGH); // Turn on LED to indicate that SMA inverter allows contactor closing
|
|
||||||
} else {
|
|
||||||
digitalWrite(INVERTER_CONTACTOR_ENABLE_LED_PIN,
|
|
||||||
LOW); // Turn off LED to indicate that SMA inverter does not allow contactor closing
|
|
||||||
}
|
|
||||||
#endif // INVERTER_CONTACTOR_ENABLE_LED_PIN
|
|
||||||
|
|
||||||
// Check if Enable line is working. If we go too long without any input, raise an event
|
// Check if Enable line is working. If we go too long without any input, raise an event
|
||||||
if (!datalayer.system.status.inverter_allows_contactor_closing) {
|
if (!datalayer.system.status.inverter_allows_contactor_closing) {
|
||||||
|
@ -276,14 +267,3 @@ void SmaBydHvsInverter::transmit_can(unsigned long currentMillis) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void SmaBydHvsInverter::setup(void) { // Performs one time setup at startup over CAN bus
|
|
||||||
strncpy(datalayer.system.info.inverter_protocol, Name, 63);
|
|
||||||
datalayer.system.info.inverter_protocol[63] = '\0';
|
|
||||||
datalayer.system.status.inverter_allows_contactor_closing = false; // The inverter needs to allow first
|
|
||||||
pinMode(INVERTER_CONTACTOR_ENABLE_PIN, INPUT);
|
|
||||||
#ifdef INVERTER_CONTACTOR_ENABLE_LED_PIN
|
|
||||||
pinMode(INVERTER_CONTACTOR_ENABLE_LED_PIN, OUTPUT);
|
|
||||||
digitalWrite(INVERTER_CONTACTOR_ENABLE_LED_PIN, LOW); // Turn LED off, until inverter allows contactor closing
|
|
||||||
#endif // INVERTER_CONTACTOR_ENABLE_LED_PIN
|
|
||||||
}
|
|
||||||
|
|
|
@ -2,23 +2,22 @@
|
||||||
#define SMA_BYD_HVS_CAN_H
|
#define SMA_BYD_HVS_CAN_H
|
||||||
#include "../include.h"
|
#include "../include.h"
|
||||||
|
|
||||||
#include "CanInverterProtocol.h"
|
#include "SmaInverterBase.h"
|
||||||
#include "src/devboard/hal/hal.h"
|
#include "src/devboard/hal/hal.h"
|
||||||
|
|
||||||
#ifdef SMA_BYD_HVS_CAN
|
#ifdef SMA_BYD_HVS_CAN
|
||||||
#define SELECTED_INVERTER_CLASS SmaBydHvsInverter
|
#define SELECTED_INVERTER_CLASS SmaBydHvsInverter
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
class SmaBydHvsInverter : public CanInverterProtocol {
|
class SmaBydHvsInverter : public SmaInverterBase {
|
||||||
public:
|
public:
|
||||||
void setup();
|
const char* name() override { return Name; }
|
||||||
void update_values();
|
void update_values();
|
||||||
void transmit_can(unsigned long currentMillis);
|
void transmit_can(unsigned long currentMillis);
|
||||||
void map_can_frame_to_variable(CAN_frame rx_frame);
|
void map_can_frame_to_variable(CAN_frame rx_frame);
|
||||||
static constexpr const char* Name = "BYD Battery-Box HVS over SMA CAN";
|
static constexpr const char* Name = "BYD Battery-Box HVS over SMA CAN";
|
||||||
|
|
||||||
virtual bool controls_contactor() { return true; }
|
virtual bool controls_contactor() { return true; }
|
||||||
virtual bool allows_contactor_closing() { return digitalRead(INVERTER_CONTACTOR_ENABLE_PIN) == 1; }
|
|
||||||
|
|
||||||
private:
|
private:
|
||||||
static const int READY_STATE = 0x03;
|
static const int READY_STATE = 0x03;
|
||||||
|
|
|
@ -107,8 +107,3 @@ void SmaLvInverter::transmit_can(unsigned long currentMillis) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void SmaLvInverter::setup(void) { // Performs one time setup at startup over CAN bus
|
|
||||||
strncpy(datalayer.system.info.inverter_protocol, Name, 63);
|
|
||||||
datalayer.system.info.inverter_protocol[63] = '\0';
|
|
||||||
}
|
|
||||||
|
|
|
@ -10,7 +10,7 @@
|
||||||
|
|
||||||
class SmaLvInverter : public CanInverterProtocol {
|
class SmaLvInverter : public CanInverterProtocol {
|
||||||
public:
|
public:
|
||||||
void setup();
|
const char* name() override { return Name; }
|
||||||
void update_values();
|
void update_values();
|
||||||
void transmit_can(unsigned long currentMillis);
|
void transmit_can(unsigned long currentMillis);
|
||||||
void map_can_frame_to_variable(CAN_frame rx_frame);
|
void map_can_frame_to_variable(CAN_frame rx_frame);
|
||||||
|
|
Some files were not shown because too many files have changed in this diff Show more
Loading…
Add table
Add a link
Reference in a new issue