Merge branch 'master' into release
This commit is contained in:
1
.gitignore
vendored
Normal file
1
.gitignore
vendored
Normal file
@@ -0,0 +1 @@
|
|||||||
|
.idea
|
||||||
1524
Board320_240.cpp
1524
Board320_240.cpp
File diff suppressed because it is too large
Load Diff
@@ -14,14 +14,18 @@
|
|||||||
|
|
||||||
//
|
//
|
||||||
#include <TFT_eSPI.h>
|
#include <TFT_eSPI.h>
|
||||||
|
#include <TinyGPS++.h>
|
||||||
#include "BoardInterface.h"
|
#include "BoardInterface.h"
|
||||||
|
|
||||||
class Board320_240 : public BoardInterface {
|
class Board320_240 : public BoardInterface {
|
||||||
|
|
||||||
private:
|
protected:
|
||||||
// TFT, SD SPI
|
// TFT, SD SPI
|
||||||
TFT_eSPI tft = TFT_eSPI();
|
TFT_eSPI tft = TFT_eSPI();
|
||||||
TFT_eSprite spr = TFT_eSprite(&tft);
|
TFT_eSprite spr = TFT_eSprite(&tft);
|
||||||
|
//SPIClass spiSD(HSPI);
|
||||||
|
HardwareSerial* gpsHwUart = NULL;
|
||||||
|
TinyGPSPlus gps;
|
||||||
char tmpStr1[20];
|
char tmpStr1[20];
|
||||||
char tmpStr2[20];
|
char tmpStr2[20];
|
||||||
char tmpStr3[20];
|
char tmpStr3[20];
|
||||||
@@ -33,11 +37,20 @@ class Board320_240 : public BoardInterface {
|
|||||||
byte pinButtonMiddle = 0;
|
byte pinButtonMiddle = 0;
|
||||||
byte pinSpeaker = 0;
|
byte pinSpeaker = 0;
|
||||||
byte pinBrightness = 0;
|
byte pinBrightness = 0;
|
||||||
//
|
byte pinSdcardCs = 0;
|
||||||
|
byte pinSdcardMosi = 0;
|
||||||
|
byte pinSdcardMiso = 0;
|
||||||
|
byte pinSdcardSclk = 0;
|
||||||
|
//
|
||||||
void initBoard() override;
|
void initBoard() override;
|
||||||
void afterSetup() override;
|
void afterSetup() override;
|
||||||
void mainLoop() override;
|
void mainLoop() override;
|
||||||
bool skipAdapterScan() override;
|
bool skipAdapterScan() override;
|
||||||
|
// SD card
|
||||||
|
bool sdcardMount() override;
|
||||||
|
void sdcardToggleRecording() override;
|
||||||
|
// GPS
|
||||||
|
void syncGPS();
|
||||||
// Basic GUI
|
// Basic GUI
|
||||||
void setBrightness(byte lcdBrightnessPerc) override;
|
void setBrightness(byte lcdBrightnessPerc) override;
|
||||||
void displayMessage(const char* row1, const char* row2) override;
|
void displayMessage(const char* row1, const char* row2) override;
|
||||||
@@ -59,7 +72,7 @@ class Board320_240 : public BoardInterface {
|
|||||||
void hideMenu() override;
|
void hideMenu() override;
|
||||||
void menuMove(bool forward);
|
void menuMove(bool forward);
|
||||||
void menuItemClick();
|
void menuItemClick();
|
||||||
//
|
//
|
||||||
void loadTestData();
|
void loadTestData();
|
||||||
//
|
//
|
||||||
};
|
};
|
||||||
|
|||||||
@@ -1,23 +1,28 @@
|
|||||||
#ifndef BOARDINTERFACE_CPP
|
#ifndef BOARDINTERFACE_CPP
|
||||||
#define BOARDINTERFACE_CPP
|
#define BOARDINTERFACE_CPP
|
||||||
|
|
||||||
|
#define ARDUINOJSON_USE_LONG_LONG 1
|
||||||
|
|
||||||
|
#include <ArduinoJson.h>
|
||||||
#include <EEPROM.h>
|
#include <EEPROM.h>
|
||||||
#include <BLEDevice.h>
|
#include <BLEDevice.h>
|
||||||
#include "BoardInterface.h"
|
#include "BoardInterface.h"
|
||||||
|
#include "CommObd2Ble4.h";
|
||||||
|
#include "CommObd2Can.h";
|
||||||
#include "LiveData.h"
|
#include "LiveData.h"
|
||||||
|
|
||||||
/**
|
/**
|
||||||
Set live data
|
Set live data
|
||||||
*/
|
*/
|
||||||
void BoardInterface::setLiveData(LiveData* pLiveData) {
|
void BoardInterface::setLiveData(LiveData* pLiveData) {
|
||||||
this->liveData = pLiveData;
|
liveData = pLiveData;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
Attach car interface
|
Attach car interface
|
||||||
*/
|
*/
|
||||||
void BoardInterface::attachCar(CarInterface* pCarInterface) {
|
void BoardInterface::attachCar(CarInterface* pCarInterface) {
|
||||||
this->carInterface = pCarInterface;
|
carInterface = pCarInterface;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@@ -28,11 +33,22 @@ void BoardInterface::shutdownDevice() {
|
|||||||
|
|
||||||
Serial.println("Shutdown.");
|
Serial.println("Shutdown.");
|
||||||
|
|
||||||
this->displayMessage("Shutdown in 3 sec.", "");
|
char msg[20];
|
||||||
delay(3000);
|
for (int i = 3; i >= 1; i--) {
|
||||||
|
sprintf(msg, "Shutdown in %d sec.", i);
|
||||||
|
displayMessage(msg, "");
|
||||||
|
delay(1000);
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef SIM800L_ENABLED
|
||||||
|
if(sim800l->isConnectedGPRS()) {
|
||||||
|
sim800l->disconnectGPRS();
|
||||||
|
}
|
||||||
|
sim800l->setPowerMode(MINIMUM);
|
||||||
|
#endif //SIM800L_ENABLED
|
||||||
|
|
||||||
setCpuFrequencyMhz(80);
|
setCpuFrequencyMhz(80);
|
||||||
this->setBrightness(0);
|
setBrightness(0);
|
||||||
//WiFi.disconnect(true);
|
//WiFi.disconnect(true);
|
||||||
//WiFi.mode(WIFI_OFF);
|
//WiFi.mode(WIFI_OFF);
|
||||||
btStop();
|
btStop();
|
||||||
@@ -52,7 +68,7 @@ void BoardInterface::saveSettings() {
|
|||||||
|
|
||||||
// Flash to memory
|
// Flash to memory
|
||||||
Serial.println("Settings saved to eeprom.");
|
Serial.println("Settings saved to eeprom.");
|
||||||
EEPROM.put(0, this->liveData->settings);
|
EEPROM.put(0, liveData->settings);
|
||||||
EEPROM.commit();
|
EEPROM.commit();
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -63,11 +79,11 @@ void BoardInterface::resetSettings() {
|
|||||||
|
|
||||||
// Flash to memory
|
// Flash to memory
|
||||||
Serial.println("Factory reset.");
|
Serial.println("Factory reset.");
|
||||||
this->liveData->settings.initFlag = 1;
|
liveData->settings.initFlag = 1;
|
||||||
EEPROM.put(0, this->liveData->settings);
|
EEPROM.put(0, liveData->settings);
|
||||||
EEPROM.commit();
|
EEPROM.commit();
|
||||||
|
|
||||||
this->displayMessage("Settings erased", "Restarting in 5 seconds");
|
displayMessage("Settings erased", "Restarting in 5 seconds");
|
||||||
|
|
||||||
delay(5000);
|
delay(5000);
|
||||||
ESP.restart();
|
ESP.restart();
|
||||||
@@ -80,72 +96,222 @@ void BoardInterface::loadSettings() {
|
|||||||
|
|
||||||
String tmpStr;
|
String tmpStr;
|
||||||
|
|
||||||
// Init
|
// Default settings
|
||||||
this->liveData->settings.initFlag = 183;
|
liveData->settings.initFlag = 183;
|
||||||
this->liveData->settings.settingsVersion = 3;
|
liveData->settings.settingsVersion = 5;
|
||||||
this->liveData->settings.carType = CAR_KIA_ENIRO_2020_64;
|
liveData->settings.carType = CAR_KIA_ENIRO_2020_64;
|
||||||
|
|
||||||
// Default OBD adapter MAC and UUID's
|
|
||||||
tmpStr = "00:00:00:00:00:00"; // Pair via menu (middle button)
|
tmpStr = "00:00:00:00:00:00"; // Pair via menu (middle button)
|
||||||
tmpStr.toCharArray(this->liveData->settings.obdMacAddress, tmpStr.length() + 1);
|
tmpStr.toCharArray(liveData->settings.obdMacAddress, tmpStr.length() + 1);
|
||||||
tmpStr = "000018f0-0000-1000-8000-00805f9b34fb"; // Default UUID's for VGate iCar Pro BLE4 adapter
|
tmpStr = "000018f0-0000-1000-8000-00805f9b34fb"; // Default UUID's for VGate iCar Pro BLE4 adapter
|
||||||
tmpStr.toCharArray(this->liveData->settings.serviceUUID, tmpStr.length() + 1);
|
tmpStr.toCharArray(liveData->settings.serviceUUID, tmpStr.length() + 1);
|
||||||
tmpStr = "00002af0-0000-1000-8000-00805f9b34fb";
|
tmpStr = "00002af0-0000-1000-8000-00805f9b34fb";
|
||||||
tmpStr.toCharArray(this->liveData->settings.charTxUUID, tmpStr.length() + 1);
|
tmpStr.toCharArray(liveData->settings.charTxUUID, tmpStr.length() + 1);
|
||||||
tmpStr = "00002af1-0000-1000-8000-00805f9b34fb";
|
tmpStr = "00002af1-0000-1000-8000-00805f9b34fb";
|
||||||
tmpStr.toCharArray(this->liveData->settings.charRxUUID, tmpStr.length() + 1);
|
tmpStr.toCharArray(liveData->settings.charRxUUID, tmpStr.length() + 1);
|
||||||
|
liveData->settings.displayRotation = 1; // 1,3
|
||||||
this->liveData->settings.displayRotation = 1; // 1,3
|
liveData->settings.distanceUnit = 'k';
|
||||||
this->liveData->settings.distanceUnit = 'k';
|
liveData->settings.temperatureUnit = 'c';
|
||||||
this->liveData->settings.temperatureUnit = 'c';
|
liveData->settings.pressureUnit = 'b';
|
||||||
this->liveData->settings.pressureUnit = 'b';
|
liveData->settings.defaultScreen = 1;
|
||||||
this->liveData->settings.defaultScreen = 1;
|
liveData->settings.lcdBrightness = 0;
|
||||||
this->liveData->settings.lcdBrightness = 0;
|
liveData->settings.debugScreen = 0;
|
||||||
this->liveData->settings.debugScreen = 0;
|
liveData->settings.predrawnChargingGraphs = 1;
|
||||||
this->liveData->settings.predrawnChargingGraphs = 1;
|
liveData->settings.commType = 0; // BLE4
|
||||||
|
liveData->settings.wifiEnabled = 0;
|
||||||
#ifdef SIM800L_ENABLED
|
tmpStr = "empty";
|
||||||
tmpStr = "internet.t-mobile.cz";
|
tmpStr.toCharArray(liveData->settings.wifiSsid, tmpStr.length() + 1);
|
||||||
|
tmpStr = "not_set";
|
||||||
|
tmpStr.toCharArray(liveData->settings.wifiPassword, tmpStr.length() + 1);
|
||||||
|
liveData->settings.ntpEnabled = 0;
|
||||||
|
liveData->settings.ntpTimezone = 1;
|
||||||
|
liveData->settings.ntpDaySaveTime = 0;
|
||||||
|
liveData->settings.sdcardEnabled = 0;
|
||||||
|
liveData->settings.sdcardAutstartLog = 1;
|
||||||
|
liveData->settings.gprsEnabled = 0;
|
||||||
|
tmpStr = "not_set";
|
||||||
tmpStr.toCharArray(liveData->settings.gprsApn, tmpStr.length() + 1);
|
tmpStr.toCharArray(liveData->settings.gprsApn, tmpStr.length() + 1);
|
||||||
tmpStr = "http://api.example.com";
|
// Remote upload
|
||||||
tmpStr.toCharArray(liveData->settings.remoteApiSrvr, tmpStr.length() + 1);
|
liveData->settings.remoteUploadEnabled = 0;
|
||||||
tmpStr = "example";
|
tmpStr = "not_set";
|
||||||
|
tmpStr.toCharArray(liveData->settings.remoteApiUrl, tmpStr.length() + 1);
|
||||||
|
tmpStr = "not_set";
|
||||||
tmpStr.toCharArray(liveData->settings.remoteApiKey, tmpStr.length() + 1);
|
tmpStr.toCharArray(liveData->settings.remoteApiKey, tmpStr.length() + 1);
|
||||||
#endif //SIM800L_ENABLED
|
liveData->settings.headlightsReminder = 0;
|
||||||
|
liveData->settings.gpsHwSerialPort = 255; // off
|
||||||
|
|
||||||
// Load settings and replace default values
|
// Load settings and replace default values
|
||||||
Serial.println("Reading settings from eeprom.");
|
Serial.println("Reading settings from eeprom.");
|
||||||
EEPROM.begin(sizeof(SETTINGS_STRUC));
|
EEPROM.begin(sizeof(SETTINGS_STRUC));
|
||||||
EEPROM.get(0, this->liveData->tmpSettings);
|
EEPROM.get(0, liveData->tmpSettings);
|
||||||
|
|
||||||
// Init flash with default settings
|
// Init flash with default settings
|
||||||
if (this->liveData->tmpSettings.initFlag != 183) {
|
if (liveData->tmpSettings.initFlag != 183) {
|
||||||
Serial.println("Settings not found. Initialization.");
|
Serial.println("Settings not found. Initialization.");
|
||||||
this->saveSettings();
|
saveSettings();
|
||||||
} else {
|
} else {
|
||||||
Serial.print("Loaded settings ver.: ");
|
Serial.print("Loaded settings ver.: ");
|
||||||
Serial.println(this->liveData->settings.settingsVersion);
|
Serial.println(liveData->tmpSettings.settingsVersion);
|
||||||
|
|
||||||
// Upgrade structure
|
// Upgrade structure
|
||||||
if (this->liveData->settings.settingsVersion != this->liveData->tmpSettings.settingsVersion) {
|
if (liveData->settings.settingsVersion != liveData->tmpSettings.settingsVersion) {
|
||||||
if (this->liveData->tmpSettings.settingsVersion == 1) {
|
if (liveData->tmpSettings.settingsVersion == 1) {
|
||||||
this->liveData->tmpSettings.settingsVersion = 2;
|
liveData->tmpSettings.settingsVersion = 2;
|
||||||
this->liveData->tmpSettings.defaultScreen = this->liveData->settings.defaultScreen;
|
liveData->tmpSettings.defaultScreen = liveData->settings.defaultScreen;
|
||||||
this->liveData->tmpSettings.lcdBrightness = this->liveData->settings.lcdBrightness;
|
liveData->tmpSettings.lcdBrightness = liveData->settings.lcdBrightness;
|
||||||
this->liveData->tmpSettings.debugScreen = this->liveData->settings.debugScreen;
|
liveData->tmpSettings.debugScreen = liveData->settings.debugScreen;
|
||||||
}
|
}
|
||||||
if (this->liveData->tmpSettings.settingsVersion == 2) {
|
if (liveData->tmpSettings.settingsVersion == 2) {
|
||||||
this->liveData->tmpSettings.settingsVersion = 3;
|
liveData->tmpSettings.settingsVersion = 3;
|
||||||
this->liveData->tmpSettings.predrawnChargingGraphs = this->liveData->settings.predrawnChargingGraphs;
|
liveData->tmpSettings.predrawnChargingGraphs = liveData->settings.predrawnChargingGraphs;
|
||||||
}
|
}
|
||||||
this->saveSettings();
|
if (liveData->tmpSettings.settingsVersion == 3) {
|
||||||
|
liveData->tmpSettings.settingsVersion = 4;
|
||||||
|
liveData->tmpSettings.commType = 0; // BLE4
|
||||||
|
liveData->tmpSettings.wifiEnabled = 0;
|
||||||
|
tmpStr = "empty";
|
||||||
|
tmpStr.toCharArray(liveData->tmpSettings.wifiSsid, tmpStr.length() + 1);
|
||||||
|
tmpStr = "not_set";
|
||||||
|
tmpStr.toCharArray(liveData->tmpSettings.wifiPassword, tmpStr.length() + 1);
|
||||||
|
liveData->tmpSettings.ntpEnabled = 0;
|
||||||
|
liveData->tmpSettings.ntpTimezone = 1;
|
||||||
|
liveData->tmpSettings.ntpDaySaveTime = 0;
|
||||||
|
liveData->tmpSettings.sdcardEnabled = 0;
|
||||||
|
liveData->tmpSettings.sdcardAutstartLog = 1;
|
||||||
|
liveData->tmpSettings.gprsEnabled = 0;
|
||||||
|
tmpStr = "internet.t-mobile.cz";
|
||||||
|
tmpStr.toCharArray(liveData->tmpSettings.gprsApn, tmpStr.length() + 1);
|
||||||
|
// Remote upload
|
||||||
|
liveData->tmpSettings.remoteUploadEnabled = 0;
|
||||||
|
tmpStr = "http://api.example.com";
|
||||||
|
tmpStr.toCharArray(liveData->tmpSettings.remoteApiUrl, tmpStr.length() + 1);
|
||||||
|
tmpStr = "example";
|
||||||
|
tmpStr.toCharArray(liveData->tmpSettings.remoteApiKey, tmpStr.length() + 1);
|
||||||
|
liveData->tmpSettings.headlightsReminder = 0;
|
||||||
|
}
|
||||||
|
if (liveData->tmpSettings.settingsVersion == 4) {
|
||||||
|
liveData->tmpSettings.settingsVersion = 5;
|
||||||
|
liveData->tmpSettings.gpsHwSerialPort = 255; // off
|
||||||
|
}
|
||||||
|
|
||||||
|
// Save upgraded structure
|
||||||
|
liveData->settings = liveData->tmpSettings;
|
||||||
|
saveSettings();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Save version? No need to upgrade structure
|
// Apply settings from flash if needed
|
||||||
if (this->liveData->settings.settingsVersion == this->liveData->tmpSettings.settingsVersion) {
|
liveData->settings = liveData->tmpSettings;
|
||||||
this->liveData->settings = this->liveData->tmpSettings;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
After setup
|
||||||
|
*/
|
||||||
|
void BoardInterface::afterSetup() {
|
||||||
|
|
||||||
|
// Init Comm iterface
|
||||||
|
if (liveData->settings.commType == COMM_TYPE_OBD2BLE4) {
|
||||||
|
commInterface = new CommObd2Ble4();
|
||||||
|
} else if (liveData->settings.commType == COMM_TYPE_OBD2CAN) {
|
||||||
|
commInterface = new CommObd2Ble4();
|
||||||
|
//commInterface = new CommObd2Can();
|
||||||
|
}
|
||||||
|
//commInterface->initComm(liveData, NULL);
|
||||||
|
commInterface->connectDevice();
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
Custom commands
|
||||||
|
*/
|
||||||
|
void BoardInterface::customConsoleCommand(String cmd) {
|
||||||
|
|
||||||
|
int8_t idx = cmd.indexOf("=");
|
||||||
|
if (idx == -1)
|
||||||
|
return;
|
||||||
|
|
||||||
|
String key = cmd.substring(0, idx);
|
||||||
|
String value = cmd.substring(idx + 1);
|
||||||
|
|
||||||
|
if (key == "serviceUUID") value.toCharArray(liveData->settings.serviceUUID, value.length() + 1);
|
||||||
|
if (key == "charTxUUID") value.toCharArray(liveData->settings.charTxUUID, value.length() + 1);
|
||||||
|
if (key == "charRxUUID") value.toCharArray(liveData->settings.charRxUUID, value.length() + 1);
|
||||||
|
if (key == "wifiSsid") value.toCharArray(liveData->settings.wifiSsid, value.length() + 1);
|
||||||
|
if (key == "wifiPassword") value.toCharArray(liveData->settings.wifiPassword, value.length() + 1);
|
||||||
|
if (key == "gprsApn") value.toCharArray(liveData->settings.gprsApn, value.length() + 1);
|
||||||
|
if (key == "remoteApiUrl") value.toCharArray(liveData->settings.remoteApiUrl, value.length() + 1);
|
||||||
|
if (key == "remoteApiKey") value.toCharArray(liveData->settings.remoteApiKey, value.length() + 1);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
Serialize parameters
|
||||||
|
*/
|
||||||
|
bool BoardInterface::serializeParamsToJson(File file, bool inclApiKey) {
|
||||||
|
|
||||||
|
StaticJsonDocument<2048> jsonData;
|
||||||
|
|
||||||
|
if (inclApiKey)
|
||||||
|
jsonData["apiKey"] = liveData->settings.remoteApiKey;
|
||||||
|
|
||||||
|
jsonData["carType"] = liveData->settings.carType;
|
||||||
|
jsonData["batTotalKwh"] = liveData->params.batteryTotalAvailableKWh;
|
||||||
|
jsonData["currTime"] = liveData->params.currentTime;
|
||||||
|
jsonData["opTime"] = liveData->params.operationTimeSec;
|
||||||
|
|
||||||
|
jsonData["gpsSat"] = liveData->params.gpsSat;
|
||||||
|
jsonData["lat"] = liveData->params.gpsLat;
|
||||||
|
jsonData["lon"] = liveData->params.gpsLon;
|
||||||
|
jsonData["alt"] = liveData->params.gpsAlt;
|
||||||
|
|
||||||
|
jsonData["socPerc"] = liveData->params.socPerc;
|
||||||
|
jsonData["sohPerc"] = liveData->params.sohPerc;
|
||||||
|
jsonData["powKwh100"] = liveData->params.batPowerKwh100;
|
||||||
|
jsonData["speedKmh"] = liveData->params.speedKmh;
|
||||||
|
jsonData["motorRpm"] = liveData->params.motorRpm;
|
||||||
|
jsonData["odoKm"] = liveData->params.odoKm;
|
||||||
|
|
||||||
|
jsonData["batPowKw"] = liveData->params.batPowerKw;
|
||||||
|
jsonData["batPowA"] = liveData->params.batPowerAmp;
|
||||||
|
jsonData["batV"] = liveData->params.batVoltage;
|
||||||
|
jsonData["cecKwh"] = liveData->params.cumulativeEnergyChargedKWh;
|
||||||
|
jsonData["cedKwh"] = liveData->params.cumulativeEnergyDischargedKWh;
|
||||||
|
jsonData["maxChKw"] = liveData->params.availableChargePower;
|
||||||
|
jsonData["maxDisKw"] = liveData->params.availableDischargePower;
|
||||||
|
|
||||||
|
jsonData["cellMinV"] = liveData->params.batCellMinV;
|
||||||
|
jsonData["cellMaxV"] = liveData->params.batCellMaxV;
|
||||||
|
jsonData["bMinC"] = round(liveData->params.batMinC);
|
||||||
|
jsonData["bMaxC"] = round(liveData->params.batMaxC);
|
||||||
|
jsonData["bHeatC"] = round(liveData->params.batHeaterC);
|
||||||
|
jsonData["bInletC"] = round(liveData->params.batInletC);
|
||||||
|
jsonData["bFanSt"] = liveData->params.batFanStatus;
|
||||||
|
jsonData["bWatC"] = round(liveData->params.coolingWaterTempC);
|
||||||
|
jsonData["tmpA"] = round(liveData->params.bmsUnknownTempA);
|
||||||
|
jsonData["tmpB"] = round(liveData->params.bmsUnknownTempB);
|
||||||
|
jsonData["tmpC"] = round(liveData->params.bmsUnknownTempC);
|
||||||
|
jsonData["tmpD"] = round(liveData->params.bmsUnknownTempD);
|
||||||
|
|
||||||
|
jsonData["auxPerc"] = liveData->params.auxPerc;
|
||||||
|
jsonData["auxV"] = liveData->params.auxVoltage;
|
||||||
|
jsonData["auxA"] = liveData->params.auxCurrentAmp;
|
||||||
|
|
||||||
|
jsonData["inC"] = liveData->params.indoorTemperature;
|
||||||
|
jsonData["outC"] = liveData->params.outdoorTemperature;
|
||||||
|
jsonData["c1C"] = liveData->params.coolantTemp1C;
|
||||||
|
jsonData["c2C"] = liveData->params.coolantTemp2C;
|
||||||
|
|
||||||
|
jsonData["tFlC"] = liveData->params.tireFrontLeftTempC;
|
||||||
|
jsonData["tFlBar"] = round(liveData->params.tireFrontLeftPressureBar * 10) / 10;
|
||||||
|
jsonData["tFrC"] = liveData->params.tireFrontRightTempC;
|
||||||
|
jsonData["tFrBar"] = round(liveData->params.tireFrontRightPressureBar * 10) / 10;
|
||||||
|
jsonData["tRlC"] = liveData->params.tireRearLeftTempC;
|
||||||
|
jsonData["tRlBar"] = round(liveData->params.tireRearLeftPressureBar * 10) / 10;
|
||||||
|
jsonData["tRrC"] = liveData->params.tireRearRightTempC;
|
||||||
|
jsonData["tRrBar"] = round(liveData->params.tireRearRightPressureBar * 10) / 10;
|
||||||
|
|
||||||
|
jsonData["debug"] = liveData->params.debugData;
|
||||||
|
jsonData["debug2"] = liveData->params.debugData2;
|
||||||
|
|
||||||
|
serializeJson(jsonData, Serial);
|
||||||
|
serializeJson(jsonData, file);
|
||||||
|
}
|
||||||
|
|
||||||
#endif // BOARDINTERFACE_CPP
|
#endif // BOARDINTERFACE_CPP
|
||||||
|
|||||||
@@ -1,12 +1,17 @@
|
|||||||
#ifndef BOARDINTERFACE_H
|
#ifndef BOARDINTERFACE_H
|
||||||
#define BOARDINTERFACE_H
|
#define BOARDINTERFACE_H
|
||||||
|
|
||||||
|
#include <FS.h>
|
||||||
#include "LiveData.h"
|
#include "LiveData.h"
|
||||||
#include "CarInterface.h"
|
#include "CarInterface.h"
|
||||||
|
#include "CommInterface.h"
|
||||||
|
|
||||||
class BoardInterface {
|
class BoardInterface {
|
||||||
|
|
||||||
private:
|
protected:
|
||||||
|
LiveData* liveData;
|
||||||
|
CarInterface* carInterface;
|
||||||
|
CommInterface* commInterface;
|
||||||
public:
|
public:
|
||||||
// Screens, buttons
|
// Screens, buttons
|
||||||
byte displayScreen = SCREEN_AUTO;
|
byte displayScreen = SCREEN_AUTO;
|
||||||
@@ -18,6 +23,7 @@ class BoardInterface {
|
|||||||
bool btnRightPressed = true;
|
bool btnRightPressed = true;
|
||||||
bool testDataMode = false;
|
bool testDataMode = false;
|
||||||
bool scanDevices = false;
|
bool scanDevices = false;
|
||||||
|
String sdcardRecordBuffer = "";
|
||||||
// Debug screen - next command with right button
|
// Debug screen - next command with right button
|
||||||
uint16_t debugCommandIndex = 0;
|
uint16_t debugCommandIndex = 0;
|
||||||
String debugAtshRequest = "ATSH7E4";
|
String debugAtshRequest = "ATSH7E4";
|
||||||
@@ -25,8 +31,6 @@ class BoardInterface {
|
|||||||
String debugLastString = "620101FFF7E7FF99000000000300B10EFE120F11100F12000018C438C30B00008400003864000035850000153A00001374000647010D017F0BDA0BDA03E8";
|
String debugLastString = "620101FFF7E7FF99000000000300B10EFE120F11100F12000018C438C30B00008400003864000035850000153A00001374000647010D017F0BDA0BDA03E8";
|
||||||
String debugPreviousString = "620101FFF7E7FFB3000000000300120F9B111011101011000014CC38CB3B00009100003A510000367C000015FB000013D3000690250D018E0000000003E8";
|
String debugPreviousString = "620101FFF7E7FFB3000000000300120F9B111011101011000014CC38CB3B00009100003A510000367C000015FB000013D3000690250D018E0000000003E8";
|
||||||
//
|
//
|
||||||
LiveData* liveData;
|
|
||||||
CarInterface* carInterface;
|
|
||||||
void setLiveData(LiveData* pLiveData);
|
void setLiveData(LiveData* pLiveData);
|
||||||
void attachCar(CarInterface* pCarInterface);
|
void attachCar(CarInterface* pCarInterface);
|
||||||
virtual void initBoard()=0;
|
virtual void initBoard()=0;
|
||||||
@@ -45,6 +49,11 @@ class BoardInterface {
|
|||||||
void saveSettings();
|
void saveSettings();
|
||||||
void resetSettings();
|
void resetSettings();
|
||||||
void loadSettings();
|
void loadSettings();
|
||||||
|
void customConsoleCommand(String cmd);
|
||||||
|
// Sdcard
|
||||||
|
virtual bool sdcardMount() {return false; };
|
||||||
|
virtual void sdcardToggleRecording()=0;
|
||||||
|
bool serializeParamsToJson(File file, bool inclApiKey = false);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // BOARDINTERFACE_H
|
#endif // BOARDINTERFACE_H
|
||||||
|
|||||||
@@ -10,15 +10,29 @@
|
|||||||
*/
|
*/
|
||||||
void BoardM5stackCore::initBoard() {
|
void BoardM5stackCore::initBoard() {
|
||||||
|
|
||||||
this->invertDisplay = true;
|
invertDisplay = true;
|
||||||
this->pinButtonLeft = BUTTON_LEFT;
|
|
||||||
this->pinButtonRight = BUTTON_RIGHT;
|
|
||||||
this->pinButtonMiddle = BUTTON_MIDDLE;
|
|
||||||
this->pinSpeaker = SPEAKER_PIN;
|
|
||||||
this->pinBrightness = TFT_BL;
|
|
||||||
|
|
||||||
Board320_240::initBoard();
|
|
||||||
|
|
||||||
|
pinButtonLeft = BUTTON_LEFT;
|
||||||
|
pinButtonRight = BUTTON_RIGHT;
|
||||||
|
pinButtonMiddle = BUTTON_MIDDLE;
|
||||||
|
pinSpeaker = SPEAKER_PIN;
|
||||||
|
pinBrightness = TFT_BL;
|
||||||
|
pinSdcardCs = SDCARD_CS;
|
||||||
|
pinSdcardMosi = SDCARD_MOSI;
|
||||||
|
pinSdcardMiso = SDCARD_MISO;
|
||||||
|
pinSdcardSclk = SDCARD_SCLK;
|
||||||
|
|
||||||
|
// Mute speaker
|
||||||
|
//ledcWriteTone(TONE_PIN_CHANNEL, 0);
|
||||||
|
digitalWrite(SPEAKER_PIN, 0);
|
||||||
|
|
||||||
|
//
|
||||||
|
Board320_240::initBoard();
|
||||||
|
}
|
||||||
|
|
||||||
|
void BoardM5stackCore::mainLoop() {
|
||||||
|
|
||||||
|
Board320_240::mainLoop();
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // BOARDM5STACKCORE_CPP
|
#endif // BOARDM5STACKCORE_CPP
|
||||||
|
|||||||
@@ -5,7 +5,6 @@
|
|||||||
#define USER_SETUP_LOADED 1
|
#define USER_SETUP_LOADED 1
|
||||||
#define SPI_FREQUENCY 27000000
|
#define SPI_FREQUENCY 27000000
|
||||||
#define SPI_TOUCH_FREQUENCY 2500000
|
#define SPI_TOUCH_FREQUENCY 2500000
|
||||||
|
|
||||||
#define USER_SETUP_LOADED 1
|
#define USER_SETUP_LOADED 1
|
||||||
#define ILI9341_DRIVER
|
#define ILI9341_DRIVER
|
||||||
#define M5STACK
|
#define M5STACK
|
||||||
@@ -18,27 +17,30 @@
|
|||||||
#define TFT_BL 32 // LED back-light
|
#define TFT_BL 32 // LED back-light
|
||||||
#define SPI_FREQUENCY 27000000
|
#define SPI_FREQUENCY 27000000
|
||||||
#define SPI_READ_FREQUENCY 5000000
|
#define SPI_READ_FREQUENCY 5000000
|
||||||
|
// BEEP PIN
|
||||||
#define SPEAKER_PIN 25
|
#define SPEAKER_PIN 25
|
||||||
|
#define TONE_PIN_CHANNEL 0
|
||||||
|
|
||||||
|
// SDCARD
|
||||||
|
#define SDCARD_CS 4
|
||||||
|
#define SDCARD_MOSI 23
|
||||||
|
#define SDCARD_MISO 19
|
||||||
|
#define SDCARD_SCLK 18
|
||||||
|
|
||||||
#define BUTTON_LEFT 37
|
#define BUTTON_LEFT 37
|
||||||
#define BUTTON_MIDDLE 38
|
#define BUTTON_MIDDLE 38
|
||||||
#define BUTTON_RIGHT 39
|
#define BUTTON_RIGHT 39
|
||||||
|
|
||||||
#define SD_CS 4
|
|
||||||
#define SD_MOSI 23
|
|
||||||
#define SD_MISO 19
|
|
||||||
#define SD_SCLK 18
|
|
||||||
|
|
||||||
//
|
//
|
||||||
#include "BoardInterface.h"
|
#include "BoardInterface.h"
|
||||||
#include "Board320_240.h"
|
#include "Board320_240.h"
|
||||||
|
|
||||||
class BoardM5stackCore : public Board320_240 {
|
class BoardM5stackCore : public Board320_240 {
|
||||||
|
|
||||||
private:
|
protected:
|
||||||
public:
|
public:
|
||||||
void initBoard() override;
|
void initBoard() override;
|
||||||
|
void mainLoop() override;
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // BOARDM5STACKCORE_H
|
#endif // BOARDM5STACKCORE_H
|
||||||
|
|||||||
@@ -10,11 +10,15 @@
|
|||||||
*/
|
*/
|
||||||
void BoardTtgoT4v13::initBoard() {
|
void BoardTtgoT4v13::initBoard() {
|
||||||
|
|
||||||
this->pinButtonLeft = BUTTON_LEFT;
|
pinButtonLeft = BUTTON_LEFT;
|
||||||
this->pinButtonRight = BUTTON_RIGHT;
|
pinButtonRight = BUTTON_RIGHT;
|
||||||
this->pinButtonMiddle = BUTTON_MIDDLE;
|
pinButtonMiddle = BUTTON_MIDDLE;
|
||||||
//this->pinSpeaker = SPEAKER_PIN;
|
//pinSpeaker = SPEAKER_PIN;
|
||||||
this->pinBrightness = TFT_BL;
|
pinBrightness = TFT_BL;
|
||||||
|
pinSdcardCs = SDCARD_CS;
|
||||||
|
pinSdcardMosi = SDCARD_MOSI;
|
||||||
|
pinSdcardMiso = SDCARD_MISO;
|
||||||
|
pinSdcardSclk = SDCARD_SCLK;
|
||||||
|
|
||||||
Board320_240::initBoard();
|
Board320_240::initBoard();
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -20,10 +20,10 @@
|
|||||||
//#define SPI_FREQUENCY 40000000 // Maximum for ILI9341
|
//#define SPI_FREQUENCY 40000000 // Maximum for ILI9341
|
||||||
#define SPI_READ_FREQUENCY 6000000 // 6 MHz is the maximum SPI read speed for the ST7789V
|
#define SPI_READ_FREQUENCY 6000000 // 6 MHz is the maximum SPI read speed for the ST7789V
|
||||||
|
|
||||||
#define SD_CS 13
|
#define SDCARD_CS 13
|
||||||
#define SD_MOSI 15
|
#define SDCARD_MOSI 15
|
||||||
#define SD_MISO 2
|
#define SDCARD_MISO 2
|
||||||
#define SD_SCLK 14
|
#define SDCARD_SCLK 14
|
||||||
|
|
||||||
#define BUTTON_LEFT 38
|
#define BUTTON_LEFT 38
|
||||||
#define BUTTON_MIDDLE 37
|
#define BUTTON_MIDDLE 37
|
||||||
@@ -36,7 +36,7 @@
|
|||||||
//
|
//
|
||||||
class BoardTtgoT4v13 : public Board320_240 {
|
class BoardTtgoT4v13 : public Board320_240 {
|
||||||
|
|
||||||
private:
|
protected:
|
||||||
public:
|
public:
|
||||||
void initBoard() override;
|
void initBoard() override;
|
||||||
|
|
||||||
|
|||||||
@@ -7,7 +7,7 @@
|
|||||||
#define commandQueueLoopFromHyundaiIoniq 8
|
#define commandQueueLoopFromHyundaiIoniq 8
|
||||||
|
|
||||||
/**
|
/**
|
||||||
activatethis->liveData->commandQueue
|
activateliveData->commandQueue
|
||||||
*/
|
*/
|
||||||
void CarHyundaiIoniq::activateCommandQueue() {
|
void CarHyundaiIoniq::activateCommandQueue() {
|
||||||
|
|
||||||
@@ -63,19 +63,19 @@ void CarHyundaiIoniq::activateCommandQueue() {
|
|||||||
};
|
};
|
||||||
|
|
||||||
// 28kWh version
|
// 28kWh version
|
||||||
this->liveData->params.batteryTotalAvailableKWh = 28;
|
liveData->params.batteryTotalAvailableKWh = 28;
|
||||||
this->liveData->params.batModuleTempCount = 12;
|
liveData->params.batModuleTempCount = 12;
|
||||||
|
|
||||||
// Empty and fill command queue
|
// Empty and fill command queue
|
||||||
for (int i = 0; i < 300; i++) {
|
for (int i = 0; i < 300; i++) {
|
||||||
this->liveData->commandQueue[i] = "";
|
liveData->commandQueue[i] = "";
|
||||||
}
|
}
|
||||||
for (int i = 0; i < commandQueueCountHyundaiIoniq; i++) {
|
for (int i = 0; i < commandQueueCountHyundaiIoniq; i++) {
|
||||||
this->liveData->commandQueue[i] = commandQueueHyundaiIoniq[i];
|
liveData->commandQueue[i] = commandQueueHyundaiIoniq[i];
|
||||||
}
|
}
|
||||||
|
|
||||||
this->liveData->commandQueueLoopFrom = commandQueueLoopFromHyundaiIoniq;
|
liveData->commandQueueLoopFrom = commandQueueLoopFromHyundaiIoniq;
|
||||||
this->liveData->commandQueueCount = commandQueueCountHyundaiIoniq;
|
liveData->commandQueueCount = commandQueueCountHyundaiIoniq;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -84,157 +84,157 @@ void CarHyundaiIoniq::activateCommandQueue() {
|
|||||||
void CarHyundaiIoniq::parseRowMerged() {
|
void CarHyundaiIoniq::parseRowMerged() {
|
||||||
|
|
||||||
// VMCU 7E2
|
// VMCU 7E2
|
||||||
if (this->liveData->currentAtshRequest.equals("ATSH7E2")) {
|
if (liveData->currentAtshRequest.equals("ATSH7E2")) {
|
||||||
if (this->liveData->commandRequest.equals("2101")) {
|
if (liveData->commandRequest.equals("2101")) {
|
||||||
this->liveData->params.speedKmh = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(32, 36).c_str(), 2, false) * 0.0155; // / 100.0 *1.609 = real to gps is 1.750
|
liveData->params.speedKmh = liveData->hexToDecFromResponse(32, 36, 2, false) * 0.0155; // / 100.0 *1.609 = real to gps is 1.750
|
||||||
if (this->liveData->params.speedKmh < -99 || this->liveData->params.speedKmh > 200)
|
if (liveData->params.speedKmh < -99 || liveData->params.speedKmh > 200)
|
||||||
this->liveData->params.speedKmh = 0;
|
liveData->params.speedKmh = 0;
|
||||||
}
|
}
|
||||||
if (this->liveData->commandRequest.equals("2102")) {
|
if (liveData->commandRequest.equals("2102")) {
|
||||||
this->liveData->params.auxPerc = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(50, 52).c_str(), 1, false);
|
liveData->params.auxPerc = liveData->hexToDecFromResponse(50, 52, 1, false);
|
||||||
this->liveData->params.auxCurrentAmp = - this->liveData->hexToDec(this->liveData->responseRowMerged.substring(46, 50).c_str(), 2, true) / 1000.0;
|
liveData->params.auxCurrentAmp = - liveData->hexToDecFromResponse(46, 50, 2, true) / 1000.0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Cluster module 7c6
|
// Cluster module 7c6
|
||||||
if (this->liveData->currentAtshRequest.equals("ATSH7C6")) {
|
if (liveData->currentAtshRequest.equals("ATSH7C6")) {
|
||||||
if (this->liveData->commandRequest.equals("22B002")) {
|
if (liveData->commandRequest.equals("22B002")) {
|
||||||
this->liveData->params.odoKm = float(strtol(this->liveData->responseRowMerged.substring(18, 24).c_str(), 0, 16));
|
liveData->params.odoKm = liveData->decFromResponse(18, 24);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Aircon 7b3
|
// Aircon 7b3
|
||||||
if (this->liveData->currentAtshRequest.equals("ATSH7B3")) {
|
if (liveData->currentAtshRequest.equals("ATSH7B3")) {
|
||||||
if (this->liveData->commandRequest.equals("220100")) {
|
if (liveData->commandRequest.equals("220100")) {
|
||||||
this->liveData->params.indoorTemperature = (this->liveData->hexToDec(this->liveData->responseRowMerged.substring(16, 18).c_str(), 1, false) / 2) - 40;
|
liveData->params.indoorTemperature = (liveData->hexToDecFromResponse(16, 18, 1, false) / 2) - 40;
|
||||||
this->liveData->params.outdoorTemperature = (this->liveData->hexToDec(this->liveData->responseRowMerged.substring(18, 20).c_str(), 1, false) / 2) - 40;
|
liveData->params.outdoorTemperature = (liveData->hexToDecFromResponse(18, 20, 1, false) / 2) - 40;
|
||||||
}
|
}
|
||||||
if (this->liveData->commandRequest.equals("220102") && this->liveData->responseRowMerged.substring(12, 14) == "00") {
|
if (liveData->commandRequest.equals("220102") && liveData->responseRowMerged.substring(12, 14) == "00") {
|
||||||
this->liveData->params.coolantTemp1C = (this->liveData->hexToDec(this->liveData->responseRowMerged.substring(14, 16).c_str(), 1, false) / 2) - 40;
|
liveData->params.coolantTemp1C = (liveData->hexToDecFromResponse(14, 16, 1, false) / 2) - 40;
|
||||||
this->liveData->params.coolantTemp2C = (this->liveData->hexToDec(this->liveData->responseRowMerged.substring(16, 18).c_str(), 1, false) / 2) - 40;
|
liveData->params.coolantTemp2C = (liveData->hexToDecFromResponse(16, 18, 1, false) / 2) - 40;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// BMS 7e4
|
// BMS 7e4
|
||||||
if (this->liveData->currentAtshRequest.equals("ATSH7E4")) {
|
if (liveData->currentAtshRequest.equals("ATSH7E4")) {
|
||||||
if (this->liveData->commandRequest.equals("2101")) {
|
if (liveData->commandRequest.equals("2101")) {
|
||||||
this->liveData->params.cumulativeEnergyChargedKWh = float(strtol(this->liveData->responseRowMerged.substring(80, 88).c_str(), 0, 16)) / 10.0;
|
liveData->params.cumulativeEnergyChargedKWh = liveData->decFromResponse(80, 88) / 10.0;
|
||||||
if (this->liveData->params.cumulativeEnergyChargedKWhStart == -1)
|
if (liveData->params.cumulativeEnergyChargedKWhStart == -1)
|
||||||
this->liveData->params.cumulativeEnergyChargedKWhStart = this->liveData->params.cumulativeEnergyChargedKWh;
|
liveData->params.cumulativeEnergyChargedKWhStart = liveData->params.cumulativeEnergyChargedKWh;
|
||||||
this->liveData->params.cumulativeEnergyDischargedKWh = float(strtol(this->liveData->responseRowMerged.substring(88, 96).c_str(), 0, 16)) / 10.0;
|
liveData->params.cumulativeEnergyDischargedKWh = liveData->decFromResponse(88, 96) / 10.0;
|
||||||
if (this->liveData->params.cumulativeEnergyDischargedKWhStart == -1)
|
if (liveData->params.cumulativeEnergyDischargedKWhStart == -1)
|
||||||
this->liveData->params.cumulativeEnergyDischargedKWhStart = this->liveData->params.cumulativeEnergyDischargedKWh;
|
liveData->params.cumulativeEnergyDischargedKWhStart = liveData->params.cumulativeEnergyDischargedKWh;
|
||||||
this->liveData->params.availableChargePower = float(strtol(this->liveData->responseRowMerged.substring(16, 20).c_str(), 0, 16)) / 100.0;
|
liveData->params.availableChargePower = liveData->decFromResponse(16, 20) / 100.0;
|
||||||
this->liveData->params.availableDischargePower = float(strtol(this->liveData->responseRowMerged.substring(20, 24).c_str(), 0, 16)) / 100.0;
|
liveData->params.availableDischargePower = liveData->decFromResponse(20, 24) / 100.0;
|
||||||
this->liveData->params.isolationResistanceKOhm = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(118, 122).c_str(), 2, true);
|
liveData->params.isolationResistanceKOhm = liveData->hexToDecFromResponse(118, 122, 2, true);
|
||||||
this->liveData->params.batFanStatus = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(58, 60).c_str(), 2, true);
|
liveData->params.batFanStatus = liveData->hexToDecFromResponse(58, 60, 2, true);
|
||||||
this->liveData->params.batFanFeedbackHz = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(60, 62).c_str(), 2, true);
|
liveData->params.batFanFeedbackHz = liveData->hexToDecFromResponse(60, 62, 2, true);
|
||||||
this->liveData->params.auxVoltage = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(62, 64).c_str(), 2, true) / 10.0;
|
liveData->params.auxVoltage = liveData->hexToDecFromResponse(62, 64, 2, true) / 10.0;
|
||||||
this->liveData->params.batPowerAmp = - this->liveData->hexToDec(this->liveData->responseRowMerged.substring(24, 28).c_str(), 2, true) / 10.0;
|
liveData->params.batPowerAmp = - liveData->hexToDecFromResponse(24, 28, 2, true) / 10.0;
|
||||||
this->liveData->params.batVoltage = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(28, 32).c_str(), 2, false) / 10.0;
|
liveData->params.batVoltage = liveData->hexToDecFromResponse(28, 32, 2, false) / 10.0;
|
||||||
this->liveData->params.batPowerKw = (this->liveData->params.batPowerAmp * this->liveData->params.batVoltage) / 1000.0;
|
liveData->params.batPowerKw = (liveData->params.batPowerAmp * liveData->params.batVoltage) / 1000.0;
|
||||||
if (this->liveData->params.batPowerKw < 1) // Reset charging start time
|
if (liveData->params.batPowerKw < 1) // Reset charging start time
|
||||||
this->liveData->params.chargingStartTime = this->liveData->params.currentTime;
|
liveData->params.chargingStartTime = liveData->params.currentTime;
|
||||||
this->liveData->params.batPowerKwh100 = this->liveData->params.batPowerKw / this->liveData->params.speedKmh * 100;
|
liveData->params.batPowerKwh100 = liveData->params.batPowerKw / liveData->params.speedKmh * 100;
|
||||||
this->liveData->params.batCellMaxV = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(50, 52).c_str(), 1, false) / 50.0;
|
liveData->params.batCellMaxV = liveData->hexToDecFromResponse(50, 52, 1, false) / 50.0;
|
||||||
this->liveData->params.batCellMinV = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(54, 56).c_str(), 1, false) / 50.0;
|
liveData->params.batCellMinV = liveData->hexToDecFromResponse(54, 56, 1, false) / 50.0;
|
||||||
this->liveData->params.batModuleTempC[0] = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(36, 38).c_str(), 1, true);
|
liveData->params.batModuleTempC[0] = liveData->hexToDecFromResponse(36, 38, 1, true);
|
||||||
this->liveData->params.batModuleTempC[1] = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(38, 40).c_str(), 1, true);
|
liveData->params.batModuleTempC[1] = liveData->hexToDecFromResponse(38, 40, 1, true);
|
||||||
this->liveData->params.batModuleTempC[2] = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(40, 42).c_str(), 1, true);
|
liveData->params.batModuleTempC[2] = liveData->hexToDecFromResponse(40, 42, 1, true);
|
||||||
this->liveData->params.batModuleTempC[3] = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(42, 44).c_str(), 1, true);
|
liveData->params.batModuleTempC[3] = liveData->hexToDecFromResponse(42, 44, 1, true);
|
||||||
this->liveData->params.batModuleTempC[4] = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(44, 46).c_str(), 1, true);
|
liveData->params.batModuleTempC[4] = liveData->hexToDecFromResponse(44, 46, 1, true);
|
||||||
//this->liveData->params.batTempC = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(34, 36).c_str(), 1, true);
|
//liveData->params.batTempC = liveData->hexToDecFromResponse(34, 36, 1, true);
|
||||||
//this->liveData->params.batMaxC = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(32, 34).c_str(), 1, true);
|
//liveData->params.batMaxC = liveData->hexToDecFromResponse(32, 34, 1, true);
|
||||||
//this->liveData->params.batMinC = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(34, 36).c_str(), 1, true);
|
//liveData->params.batMinC = liveData->hexToDecFromResponse(34, 36, 1, true);
|
||||||
|
|
||||||
// This is more accurate than min/max from BMS. It's required to detect kona/eniro cold gates (min 15C is needed > 43kW charging, min 25C is needed > 58kW charging)
|
// This is more accurate than min/max from BMS. It's required to detect kona/eniro cold gates (min 15C is needed > 43kW charging, min 25C is needed > 58kW charging)
|
||||||
this->liveData->params.batInletC = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(48, 50).c_str(), 1, true);
|
liveData->params.batInletC = liveData->hexToDecFromResponse(48, 50, 1, true);
|
||||||
if (this->liveData->params.speedKmh < 10 && this->liveData->params.batPowerKw >= 1 && this->liveData->params.socPerc > 0 && this->liveData->params.socPerc <= 100) {
|
if (liveData->params.speedKmh < 10 && liveData->params.batPowerKw >= 1 && liveData->params.socPerc > 0 && liveData->params.socPerc <= 100) {
|
||||||
if ( this->liveData->params.chargingGraphMinKw[int(this->liveData->params.socPerc)] == -100 || this->liveData->params.batPowerKw < this->liveData->params.chargingGraphMinKw[int(this->liveData->params.socPerc)])
|
if ( liveData->params.chargingGraphMinKw[int(liveData->params.socPerc)] == -100 || liveData->params.batPowerKw < liveData->params.chargingGraphMinKw[int(liveData->params.socPerc)])
|
||||||
this->liveData->params.chargingGraphMinKw[int(this->liveData->params.socPerc)] = this->liveData->params.batPowerKw;
|
liveData->params.chargingGraphMinKw[int(liveData->params.socPerc)] = liveData->params.batPowerKw;
|
||||||
if ( this->liveData->params.chargingGraphMaxKw[int(this->liveData->params.socPerc)] == -100 || this->liveData->params.batPowerKw > this->liveData->params.chargingGraphMaxKw[int(this->liveData->params.socPerc)])
|
if ( liveData->params.chargingGraphMaxKw[int(liveData->params.socPerc)] == -100 || liveData->params.batPowerKw > liveData->params.chargingGraphMaxKw[int(liveData->params.socPerc)])
|
||||||
this->liveData->params.chargingGraphMaxKw[int(this->liveData->params.socPerc)] = this->liveData->params.batPowerKw;
|
liveData->params.chargingGraphMaxKw[int(liveData->params.socPerc)] = liveData->params.batPowerKw;
|
||||||
this->liveData->params.chargingGraphBatMinTempC[int(this->liveData->params.socPerc)] = this->liveData->params.batMinC;
|
liveData->params.chargingGraphBatMinTempC[int(liveData->params.socPerc)] = liveData->params.batMinC;
|
||||||
this->liveData->params.chargingGraphBatMaxTempC[int(this->liveData->params.socPerc)] = this->liveData->params.batMaxC;
|
liveData->params.chargingGraphBatMaxTempC[int(liveData->params.socPerc)] = liveData->params.batMaxC;
|
||||||
this->liveData->params.chargingGraphHeaterTempC[int(this->liveData->params.socPerc)] = this->liveData->params.batHeaterC;
|
liveData->params.chargingGraphHeaterTempC[int(liveData->params.socPerc)] = liveData->params.batHeaterC;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
// BMS 7e4
|
// BMS 7e4
|
||||||
if (this->liveData->commandRequest.equals("2102") && this->liveData->responseRowMerged.substring(10, 12) == "FF") {
|
if (liveData->commandRequest.equals("2102") && liveData->responseRowMerged.substring(10, 12) == "FF") {
|
||||||
for (int i = 0; i < 32; i++) {
|
for (int i = 0; i < 32; i++) {
|
||||||
this->liveData->params.cellVoltage[i] = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(12 + (i * 2), 12 + (i * 2) + 2).c_str(), 1, false) / 50;
|
liveData->params.cellVoltage[i] = liveData->hexToDecFromResponse(12 + (i * 2), 12 + (i * 2) + 2, 1, false) / 50;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
// BMS 7e4
|
// BMS 7e4
|
||||||
if (this->liveData->commandRequest.equals("2103")) {
|
if (liveData->commandRequest.equals("2103")) {
|
||||||
for (int i = 0; i < 32; i++) {
|
for (int i = 0; i < 32; i++) {
|
||||||
this->liveData->params.cellVoltage[32 + i] = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(12 + (i * 2), 12 + (i * 2) + 2).c_str(), 1, false) / 50;
|
liveData->params.cellVoltage[32 + i] = liveData->hexToDecFromResponse(12 + (i * 2), 12 + (i * 2) + 2, 1, false) / 50;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
// BMS 7e4
|
// BMS 7e4
|
||||||
if (this->liveData->commandRequest.equals("2104")) {
|
if (liveData->commandRequest.equals("2104")) {
|
||||||
for (int i = 0; i < 32; i++) {
|
for (int i = 0; i < 32; i++) {
|
||||||
this->liveData->params.cellVoltage[64 + i] = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(12 + (i * 2), 12 + (i * 2) + 2).c_str(), 1, false) / 50;
|
liveData->params.cellVoltage[64 + i] = liveData->hexToDecFromResponse(12 + (i * 2), 12 + (i * 2) + 2, 1, false) / 50;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
// BMS 7e4
|
// BMS 7e4
|
||||||
if (this->liveData->commandRequest.equals("2105")) {
|
if (liveData->commandRequest.equals("2105")) {
|
||||||
this->liveData->params.socPercPrevious = this->liveData->params.socPerc;
|
liveData->params.socPercPrevious = liveData->params.socPerc;
|
||||||
this->liveData->params.sohPerc = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(54, 58).c_str(), 2, false) / 10.0;
|
liveData->params.sohPerc = liveData->hexToDecFromResponse(54, 58, 2, false) / 10.0;
|
||||||
this->liveData->params.socPerc = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(66, 68).c_str(), 1, false) / 2.0;
|
liveData->params.socPerc = liveData->hexToDecFromResponse(66, 68, 1, false) / 2.0;
|
||||||
|
|
||||||
// Remaining battery modules (tempC)
|
// Remaining battery modules (tempC)
|
||||||
this->liveData->params.batModuleTempC[5] = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(22, 24).c_str(), 1, true);
|
liveData->params.batModuleTempC[5] = liveData->hexToDecFromResponse(22, 24, 1, true);
|
||||||
this->liveData->params.batModuleTempC[6] = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(24, 26).c_str(), 1, true);
|
liveData->params.batModuleTempC[6] = liveData->hexToDecFromResponse(24, 26, 1, true);
|
||||||
this->liveData->params.batModuleTempC[7] = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(26, 28).c_str(), 1, true);
|
liveData->params.batModuleTempC[7] = liveData->hexToDecFromResponse(26, 28, 1, true);
|
||||||
this->liveData->params.batModuleTempC[8] = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(28, 30).c_str(), 1, true);
|
liveData->params.batModuleTempC[8] = liveData->hexToDecFromResponse(28, 30, 1, true);
|
||||||
this->liveData->params.batModuleTempC[9] = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(30, 32).c_str(), 1, true);
|
liveData->params.batModuleTempC[9] = liveData->hexToDecFromResponse(30, 32, 1, true);
|
||||||
this->liveData->params.batModuleTempC[10] = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(32, 34).c_str(), 1, true);
|
liveData->params.batModuleTempC[10] = liveData->hexToDecFromResponse(32, 34, 1, true);
|
||||||
this->liveData->params.batModuleTempC[11] = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(34, 36).c_str(), 1, true);
|
liveData->params.batModuleTempC[11] = liveData->hexToDecFromResponse(34, 36, 1, true);
|
||||||
|
|
||||||
this->liveData->params.batMinC = this->liveData->params.batMaxC = this->liveData->params.batModuleTempC[0];
|
liveData->params.batMinC = liveData->params.batMaxC = liveData->params.batModuleTempC[0];
|
||||||
for (uint16_t i = 1; i < this->liveData->params.batModuleTempCount; i++) {
|
for (uint16_t i = 1; i < liveData->params.batModuleTempCount; i++) {
|
||||||
if (this->liveData->params.batModuleTempC[i] < this->liveData->params.batMinC)
|
if (liveData->params.batModuleTempC[i] < liveData->params.batMinC)
|
||||||
this->liveData->params.batMinC = this->liveData->params.batModuleTempC[i];
|
liveData->params.batMinC = liveData->params.batModuleTempC[i];
|
||||||
if (this->liveData->params.batModuleTempC[i] > this->liveData->params.batMaxC)
|
if (liveData->params.batModuleTempC[i] > liveData->params.batMaxC)
|
||||||
this->liveData->params.batMaxC = this->liveData->params.batModuleTempC[i];
|
liveData->params.batMaxC = liveData->params.batModuleTempC[i];
|
||||||
}
|
}
|
||||||
this->liveData->params.batTempC = this->liveData->params.batMinC;
|
liveData->params.batTempC = liveData->params.batMinC;
|
||||||
|
|
||||||
// Soc10ced table, record x0% CEC/CED table (ex. 90%->89%, 80%->79%)
|
// Soc10ced table, record x0% CEC/CED table (ex. 90%->89%, 80%->79%)
|
||||||
if (this->liveData->params.socPercPrevious - this->liveData->params.socPerc > 0) {
|
if (liveData->params.socPercPrevious - liveData->params.socPerc > 0) {
|
||||||
byte index = (int(this->liveData->params.socPerc) == 4) ? 0 : (int)(this->liveData->params.socPerc / 10) + 1;
|
byte index = (int(liveData->params.socPerc) == 4) ? 0 : (int)(liveData->params.socPerc / 10) + 1;
|
||||||
if ((int(this->liveData->params.socPerc) % 10 == 9 || int(this->liveData->params.socPerc) == 4) && this->liveData->params.soc10ced[index] == -1) {
|
if ((int(liveData->params.socPerc) % 10 == 9 || int(liveData->params.socPerc) == 4) && liveData->params.soc10ced[index] == -1) {
|
||||||
this->liveData->params.soc10ced[index] = this->liveData->params.cumulativeEnergyDischargedKWh;
|
liveData->params.soc10ced[index] = liveData->params.cumulativeEnergyDischargedKWh;
|
||||||
this->liveData->params.soc10cec[index] = this->liveData->params.cumulativeEnergyChargedKWh;
|
liveData->params.soc10cec[index] = liveData->params.cumulativeEnergyChargedKWh;
|
||||||
this->liveData->params.soc10odo[index] = this->liveData->params.odoKm;
|
liveData->params.soc10odo[index] = liveData->params.odoKm;
|
||||||
this->liveData->params.soc10time[index] = this->liveData->params.currentTime;
|
liveData->params.soc10time[index] = liveData->params.currentTime;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
this->liveData->params.batHeaterC = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(50, 52).c_str(), 1, true);
|
liveData->params.batHeaterC = liveData->hexToDecFromResponse(50, 52, 1, true);
|
||||||
//
|
//
|
||||||
for (int i = 30; i < 32; i++) { // ai/aj position
|
for (int i = 30; i < 32; i++) { // ai/aj position
|
||||||
this->liveData->params.cellVoltage[96 - 30 + i] = -1;
|
liveData->params.cellVoltage[96 - 30 + i] = -1;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
// BMS 7e4
|
// BMS 7e4
|
||||||
// IONIQ FAILED
|
// IONIQ FAILED
|
||||||
if (this->liveData->commandRequest.equals("2106")) {
|
if (liveData->commandRequest.equals("2106")) {
|
||||||
this->liveData->params.coolingWaterTempC = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(14, 16).c_str(), 1, false);
|
liveData->params.coolingWaterTempC = liveData->hexToDecFromResponse(14, 16, 1, false);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// TPMS 7a0
|
// TPMS 7a0
|
||||||
if (this->liveData->currentAtshRequest.equals("ATSH7A0")) {
|
if (liveData->currentAtshRequest.equals("ATSH7A0")) {
|
||||||
if (this->liveData->commandRequest.equals("22c00b")) {
|
if (liveData->commandRequest.equals("22c00b")) {
|
||||||
this->liveData->params.tireFrontLeftPressureBar = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(14, 16).c_str(), 2, false) / 72.51886900361; // === OK Valid *0.2 / 14.503773800722
|
liveData->params.tireFrontLeftPressureBar = liveData->hexToDecFromResponse(14, 16, 2, false) / 72.51886900361; // === OK Valid *0.2 / 14.503773800722
|
||||||
this->liveData->params.tireFrontRightPressureBar = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(22, 24).c_str(), 2, false) / 72.51886900361; // === OK Valid *0.2 / 14.503773800722
|
liveData->params.tireFrontRightPressureBar = liveData->hexToDecFromResponse(22, 24, 2, false) / 72.51886900361; // === OK Valid *0.2 / 14.503773800722
|
||||||
this->liveData->params.tireRearRightPressureBar = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(30, 32).c_str(), 2, false) / 72.51886900361; // === OK Valid *0.2 / 14.503773800722
|
liveData->params.tireRearRightPressureBar = liveData->hexToDecFromResponse(30, 32, 2, false) / 72.51886900361; // === OK Valid *0.2 / 14.503773800722
|
||||||
this->liveData->params.tireRearLeftPressureBar = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(38, 40).c_str(), 2, false) / 72.51886900361; // === OK Valid *0.2 / 14.503773800722
|
liveData->params.tireRearLeftPressureBar = liveData->hexToDecFromResponse(38, 40, 2, false) / 72.51886900361; // === OK Valid *0.2 / 14.503773800722
|
||||||
this->liveData->params.tireFrontLeftTempC = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(16, 18).c_str(), 2, false) - 50; // === OK Valid
|
liveData->params.tireFrontLeftTempC = liveData->hexToDecFromResponse(16, 18, 2, false) - 50; // === OK Valid
|
||||||
this->liveData->params.tireFrontRightTempC = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(24, 26).c_str(), 2, false) - 50; // === OK Valid
|
liveData->params.tireFrontRightTempC = liveData->hexToDecFromResponse(24, 26, 2, false) - 50; // === OK Valid
|
||||||
this->liveData->params.tireRearRightTempC = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(32, 34).c_str(), 2, false) - 50; // === OK Valid
|
liveData->params.tireRearRightTempC = liveData->hexToDecFromResponse(32, 34, 2, false) - 50; // === OK Valid
|
||||||
this->liveData->params.tireRearLeftTempC = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(40, 42).c_str(), 2, false) - 50; // === OK Valid
|
liveData->params.tireRearLeftTempC = liveData->hexToDecFromResponse(40, 42, 2, false) - 50; // === OK Valid
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -246,134 +246,134 @@ void CarHyundaiIoniq::parseRowMerged() {
|
|||||||
void CarHyundaiIoniq::loadTestData() {
|
void CarHyundaiIoniq::loadTestData() {
|
||||||
|
|
||||||
// VMCU ATSH7E2
|
// VMCU ATSH7E2
|
||||||
this->liveData->currentAtshRequest = "ATSH7E2";
|
liveData->currentAtshRequest = "ATSH7E2";
|
||||||
// 2101
|
// 2101
|
||||||
this->liveData->commandRequest = "2101";
|
liveData->commandRequest = "2101";
|
||||||
this->liveData->responseRowMerged = "6101FFE0000009211222062F03000000001D7734";
|
liveData->responseRowMerged = "6101FFE0000009211222062F03000000001D7734";
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
// 2102
|
// 2102
|
||||||
this->liveData->commandRequest = "2102";
|
liveData->commandRequest = "2102";
|
||||||
this->liveData->responseRowMerged = "6102FF80000001010000009315B2888D390B08618B683900000000";
|
liveData->responseRowMerged = "6102FF80000001010000009315B2888D390B08618B683900000000";
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
|
|
||||||
// "ATSH7DF",
|
// "ATSH7DF",
|
||||||
this->liveData->currentAtshRequest = "ATSH7DF";
|
liveData->currentAtshRequest = "ATSH7DF";
|
||||||
|
|
||||||
// AIRCON / ACU ATSH7B3
|
// AIRCON / ACU ATSH7B3
|
||||||
this->liveData->currentAtshRequest = "ATSH7B3";
|
liveData->currentAtshRequest = "ATSH7B3";
|
||||||
// 220100
|
// 220100
|
||||||
this->liveData->commandRequest = "220100";
|
liveData->commandRequest = "220100";
|
||||||
this->liveData->responseRowMerged = "6201007E5007C8FF8A876A011010FFFF10FF10FFFFFFFFFFFFFFFFFF2EEF767D00FFFF00FFFF000000";
|
liveData->responseRowMerged = "6201007E5007C8FF8A876A011010FFFF10FF10FFFFFFFFFFFFFFFFFF2EEF767D00FFFF00FFFF000000";
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
// 220102
|
// 220102
|
||||||
this->liveData->commandRequest = "220102";
|
liveData->commandRequest = "220102";
|
||||||
this->liveData->responseRowMerged = "620102FF800000A3950000000000002600000000";
|
liveData->responseRowMerged = "620102FF800000A3950000000000002600000000";
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
|
|
||||||
// BMS ATSH7E4
|
// BMS ATSH7E4
|
||||||
this->liveData->currentAtshRequest = "ATSH7E4";
|
liveData->currentAtshRequest = "ATSH7E4";
|
||||||
// 220101
|
// 220101
|
||||||
this->liveData->commandRequest = "2101";
|
liveData->commandRequest = "2101";
|
||||||
this->liveData->responseRowMerged = "6101FFFFFFFF5026482648A3FFC30D9E181717171718170019B50FB501000090000142230001425F0000771B00007486007815D809015C0000000003E800";
|
liveData->responseRowMerged = "6101FFFFFFFF5026482648A3FFC30D9E181717171718170019B50FB501000090000142230001425F0000771B00007486007815D809015C0000000003E800";
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
// 220102
|
// 220102
|
||||||
this->liveData->commandRequest = "2102";
|
liveData->commandRequest = "2102";
|
||||||
this->liveData->responseRowMerged = "6102FFFFFFFFB5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5000000";
|
liveData->responseRowMerged = "6102FFFFFFFFB5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5000000";
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
// 220103
|
// 220103
|
||||||
this->liveData->commandRequest = "2103";
|
liveData->commandRequest = "2103";
|
||||||
this->liveData->responseRowMerged = "6103FFFFFFFFB5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5000000";
|
liveData->responseRowMerged = "6103FFFFFFFFB5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5000000";
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
// 220104
|
// 220104
|
||||||
this->liveData->commandRequest = "2104";
|
liveData->commandRequest = "2104";
|
||||||
this->liveData->responseRowMerged = "6104FFFFFFFFB5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5000000";
|
liveData->responseRowMerged = "6104FFFFFFFFB5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5000000";
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
// 220105
|
// 220105
|
||||||
this->liveData->commandRequest = "2105";
|
liveData->commandRequest = "2105";
|
||||||
this->liveData->responseRowMerged = "6105FFFFFFFF00000000001717171817171726482648000150181703E81A03E801520029000000000000000000000000";
|
liveData->responseRowMerged = "6105FFFFFFFF00000000001717171817171726482648000150181703E81A03E801520029000000000000000000000000";
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
// 220106
|
// 220106
|
||||||
this->liveData->commandRequest = "2106";
|
liveData->commandRequest = "2106";
|
||||||
this->liveData->responseRowMerged = "7F2112"; // n/a on ioniq
|
liveData->responseRowMerged = "7F2112"; // n/a on ioniq
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
|
|
||||||
// BCM / TPMS ATSH7A0
|
// BCM / TPMS ATSH7A0
|
||||||
this->liveData->currentAtshRequest = "ATSH7A0";
|
liveData->currentAtshRequest = "ATSH7A0";
|
||||||
// 22c00b
|
// 22c00b
|
||||||
this->liveData->commandRequest = "22c00b";
|
liveData->commandRequest = "22c00b";
|
||||||
this->liveData->responseRowMerged = "62C00BFFFF0000B9510100B9510100B84F0100B54F0100AAAAAAAA";
|
liveData->responseRowMerged = "62C00BFFFF0000B9510100B9510100B84F0100B54F0100AAAAAAAA";
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
|
|
||||||
// ATSH7C6
|
// ATSH7C6
|
||||||
this->liveData->currentAtshRequest = "ATSH7C6";
|
liveData->currentAtshRequest = "ATSH7C6";
|
||||||
// 22b002
|
// 22b002
|
||||||
this->liveData->commandRequest = "22b002";
|
liveData->commandRequest = "22b002";
|
||||||
this->liveData->responseRowMerged = "62B002E000000000AD003D2D0000000000000000";
|
liveData->responseRowMerged = "62B002E000000000AD003D2D0000000000000000";
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
|
|
||||||
/* this->liveData->params.batModule01TempC = 28;
|
/* liveData->params.batModule01TempC = 28;
|
||||||
this->liveData->params.batModule02TempC = 29;
|
liveData->params.batModule02TempC = 29;
|
||||||
this->liveData->params.batModule03TempC = 28;
|
liveData->params.batModule03TempC = 28;
|
||||||
this->liveData->params.batModule04TempC = 30;
|
liveData->params.batModule04TempC = 30;
|
||||||
//this->liveData->params.batTempC = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(36, 38).c_str(), 1, true);
|
//liveData->params.batTempC = liveData->hexToDecFromResponse(36, 38, 1, true);
|
||||||
//this->liveData->params.batMaxC = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(34, 36).c_str(), 1, true);
|
//liveData->params.batMaxC = liveData->hexToDecFromResponse(34, 36, 1, true);
|
||||||
//this->liveData->params.batMinC = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(36, 38).c_str(), 1, true);
|
//liveData->params.batMinC = liveData->hexToDecFromResponse(36, 38, 1, true);
|
||||||
|
|
||||||
// This is more accurate than min/max from BMS. It's required to detect kona/eniro cold gates (min 15C is needed > 43kW charging, min 25C is needed > 58kW charging)
|
// This is more accurate than min/max from BMS. It's required to detect kona/eniro cold gates (min 15C is needed > 43kW charging, min 25C is needed > 58kW charging)
|
||||||
this->liveData->params.batMinC = this->liveData->params.batMaxC = this->liveData->params.batModule01TempC;
|
liveData->params.batMinC = liveData->params.batMaxC = liveData->params.batModule01TempC;
|
||||||
this->liveData->params.batMinC = (this->liveData->params.batModule02TempC < this->liveData->params.batMinC) ? this->liveData->params.batModule02TempC : this->liveData->params.batMinC ;
|
liveData->params.batMinC = (liveData->params.batModule02TempC < liveData->params.batMinC) ? liveData->params.batModule02TempC : liveData->params.batMinC ;
|
||||||
this->liveData->params.batMinC = (this->liveData->params.batModule03TempC < this->liveData->params.batMinC) ? this->liveData->params.batModule03TempC : this->liveData->params.batMinC ;
|
liveData->params.batMinC = (liveData->params.batModule03TempC < liveData->params.batMinC) ? liveData->params.batModule03TempC : liveData->params.batMinC ;
|
||||||
this->liveData->params.batMinC = (this->liveData->params.batModule04TempC < this->liveData->params.batMinC) ? this->liveData->params.batModule04TempC : this->liveData->params.batMinC ;
|
liveData->params.batMinC = (liveData->params.batModule04TempC < liveData->params.batMinC) ? liveData->params.batModule04TempC : liveData->params.batMinC ;
|
||||||
this->liveData->params.batMaxC = (this->liveData->params.batModule02TempC > this->liveData->params.batMaxC) ? this->liveData->params.batModule02TempC : this->liveData->params.batMaxC ;
|
liveData->params.batMaxC = (liveData->params.batModule02TempC > liveData->params.batMaxC) ? liveData->params.batModule02TempC : liveData->params.batMaxC ;
|
||||||
this->liveData->params.batMaxC = (this->liveData->params.batModule03TempC > this->liveData->params.batMaxC) ? this->liveData->params.batModule03TempC : this->liveData->params.batMaxC ;
|
liveData->params.batMaxC = (liveData->params.batModule03TempC > liveData->params.batMaxC) ? liveData->params.batModule03TempC : liveData->params.batMaxC ;
|
||||||
this->liveData->params.batMaxC = (this->liveData->params.batModule04TempC > this->liveData->params.batMaxC) ? this->liveData->params.batModule04TempC : this->liveData->params.batMaxC ;
|
liveData->params.batMaxC = (liveData->params.batModule04TempC > liveData->params.batMaxC) ? liveData->params.batModule04TempC : liveData->params.batMaxC ;
|
||||||
this->liveData->params.batTempC = this->liveData->params.batMinC;
|
liveData->params.batTempC = liveData->params.batMinC;
|
||||||
|
|
||||||
//
|
//
|
||||||
this->liveData->params.soc10ced[10] = 2200;
|
liveData->params.soc10ced[10] = 2200;
|
||||||
this->liveData->params.soc10cec[10] = 2500;
|
liveData->params.soc10cec[10] = 2500;
|
||||||
this->liveData->params.soc10odo[10] = 13000;
|
liveData->params.soc10odo[10] = 13000;
|
||||||
this->liveData->params.soc10time[10] = 13000;
|
liveData->params.soc10time[10] = 13000;
|
||||||
this->liveData->params.soc10ced[9] = this->liveData->params.soc10ced[10] + 6.4;
|
liveData->params.soc10ced[9] = liveData->params.soc10ced[10] + 6.4;
|
||||||
this->liveData->params.soc10cec[9] = this->liveData->params.soc10cec[10] + 0;
|
liveData->params.soc10cec[9] = liveData->params.soc10cec[10] + 0;
|
||||||
this->liveData->params.soc10odo[9] = this->liveData->params.soc10odo[10] + 30;
|
liveData->params.soc10odo[9] = liveData->params.soc10odo[10] + 30;
|
||||||
this->liveData->params.soc10time[9] = this->liveData->params.soc10time[10] + 900;
|
liveData->params.soc10time[9] = liveData->params.soc10time[10] + 900;
|
||||||
this->liveData->params.soc10ced[8] = this->liveData->params.soc10ced[9] + 6.8;
|
liveData->params.soc10ced[8] = liveData->params.soc10ced[9] + 6.8;
|
||||||
this->liveData->params.soc10cec[8] = this->liveData->params.soc10cec[9] + 0;
|
liveData->params.soc10cec[8] = liveData->params.soc10cec[9] + 0;
|
||||||
this->liveData->params.soc10odo[8] = this->liveData->params.soc10odo[9] + 30;
|
liveData->params.soc10odo[8] = liveData->params.soc10odo[9] + 30;
|
||||||
this->liveData->params.soc10time[8] = this->liveData->params.soc10time[9] + 900;
|
liveData->params.soc10time[8] = liveData->params.soc10time[9] + 900;
|
||||||
this->liveData->params.soc10ced[7] = this->liveData->params.soc10ced[8] + 7.2;
|
liveData->params.soc10ced[7] = liveData->params.soc10ced[8] + 7.2;
|
||||||
this->liveData->params.soc10cec[7] = this->liveData->params.soc10cec[8] + 0.6;
|
liveData->params.soc10cec[7] = liveData->params.soc10cec[8] + 0.6;
|
||||||
this->liveData->params.soc10odo[7] = this->liveData->params.soc10odo[8] + 30;
|
liveData->params.soc10odo[7] = liveData->params.soc10odo[8] + 30;
|
||||||
this->liveData->params.soc10time[7] = this->liveData->params.soc10time[8] + 900;
|
liveData->params.soc10time[7] = liveData->params.soc10time[8] + 900;
|
||||||
this->liveData->params.soc10ced[6] = this->liveData->params.soc10ced[7] + 6.7;
|
liveData->params.soc10ced[6] = liveData->params.soc10ced[7] + 6.7;
|
||||||
this->liveData->params.soc10cec[6] = this->liveData->params.soc10cec[7] + 0;
|
liveData->params.soc10cec[6] = liveData->params.soc10cec[7] + 0;
|
||||||
this->liveData->params.soc10odo[6] = this->liveData->params.soc10odo[7] + 30;
|
liveData->params.soc10odo[6] = liveData->params.soc10odo[7] + 30;
|
||||||
this->liveData->params.soc10time[6] = this->liveData->params.soc10time[7] + 900;
|
liveData->params.soc10time[6] = liveData->params.soc10time[7] + 900;
|
||||||
this->liveData->params.soc10ced[5] = this->liveData->params.soc10ced[6] + 6.7;
|
liveData->params.soc10ced[5] = liveData->params.soc10ced[6] + 6.7;
|
||||||
this->liveData->params.soc10cec[5] = this->liveData->params.soc10cec[6] + 0;
|
liveData->params.soc10cec[5] = liveData->params.soc10cec[6] + 0;
|
||||||
this->liveData->params.soc10odo[5] = this->liveData->params.soc10odo[6] + 30;
|
liveData->params.soc10odo[5] = liveData->params.soc10odo[6] + 30;
|
||||||
this->liveData->params.soc10time[5] = this->liveData->params.soc10time[6] + 900;
|
liveData->params.soc10time[5] = liveData->params.soc10time[6] + 900;
|
||||||
this->liveData->params.soc10ced[4] = this->liveData->params.soc10ced[5] + 6.4;
|
liveData->params.soc10ced[4] = liveData->params.soc10ced[5] + 6.4;
|
||||||
this->liveData->params.soc10cec[4] = this->liveData->params.soc10cec[5] + 0.3;
|
liveData->params.soc10cec[4] = liveData->params.soc10cec[5] + 0.3;
|
||||||
this->liveData->params.soc10odo[4] = this->liveData->params.soc10odo[5] + 30;
|
liveData->params.soc10odo[4] = liveData->params.soc10odo[5] + 30;
|
||||||
this->liveData->params.soc10time[4] = this->liveData->params.soc10time[5] + 900;
|
liveData->params.soc10time[4] = liveData->params.soc10time[5] + 900;
|
||||||
this->liveData->params.soc10ced[3] = this->liveData->params.soc10ced[4] + 6.4;
|
liveData->params.soc10ced[3] = liveData->params.soc10ced[4] + 6.4;
|
||||||
this->liveData->params.soc10cec[3] = this->liveData->params.soc10cec[4] + 0;
|
liveData->params.soc10cec[3] = liveData->params.soc10cec[4] + 0;
|
||||||
this->liveData->params.soc10odo[3] = this->liveData->params.soc10odo[4] + 30;
|
liveData->params.soc10odo[3] = liveData->params.soc10odo[4] + 30;
|
||||||
this->liveData->params.soc10time[3] = this->liveData->params.soc10time[4] + 900;
|
liveData->params.soc10time[3] = liveData->params.soc10time[4] + 900;
|
||||||
this->liveData->params.soc10ced[2] = this->liveData->params.soc10ced[3] + 5.4;
|
liveData->params.soc10ced[2] = liveData->params.soc10ced[3] + 5.4;
|
||||||
this->liveData->params.soc10cec[2] = this->liveData->params.soc10cec[3] + 0.1;
|
liveData->params.soc10cec[2] = liveData->params.soc10cec[3] + 0.1;
|
||||||
this->liveData->params.soc10odo[2] = this->liveData->params.soc10odo[3] + 30;
|
liveData->params.soc10odo[2] = liveData->params.soc10odo[3] + 30;
|
||||||
this->liveData->params.soc10time[2] = this->liveData->params.soc10time[3] + 900;
|
liveData->params.soc10time[2] = liveData->params.soc10time[3] + 900;
|
||||||
this->liveData->params.soc10ced[1] = this->liveData->params.soc10ced[2] + 6.2;
|
liveData->params.soc10ced[1] = liveData->params.soc10ced[2] + 6.2;
|
||||||
this->liveData->params.soc10cec[1] = this->liveData->params.soc10cec[2] + 0.1;
|
liveData->params.soc10cec[1] = liveData->params.soc10cec[2] + 0.1;
|
||||||
this->liveData->params.soc10odo[1] = this->liveData->params.soc10odo[2] + 30;
|
liveData->params.soc10odo[1] = liveData->params.soc10odo[2] + 30;
|
||||||
this->liveData->params.soc10time[1] = this->liveData->params.soc10time[2] + 900;
|
liveData->params.soc10time[1] = liveData->params.soc10time[2] + 900;
|
||||||
this->liveData->params.soc10ced[0] = this->liveData->params.soc10ced[1] + 2.9;
|
liveData->params.soc10ced[0] = liveData->params.soc10ced[1] + 2.9;
|
||||||
this->liveData->params.soc10cec[0] = this->liveData->params.soc10cec[1] + 0.5;
|
liveData->params.soc10cec[0] = liveData->params.soc10cec[1] + 0.5;
|
||||||
this->liveData->params.soc10odo[0] = this->liveData->params.soc10odo[1] + 15;
|
liveData->params.soc10odo[0] = liveData->params.soc10odo[1] + 15;
|
||||||
this->liveData->params.soc10time[0] = this->liveData->params.soc10time[1] + 900;
|
liveData->params.soc10time[0] = liveData->params.soc10time[1] + 900;
|
||||||
*/
|
*/
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -5,7 +5,7 @@
|
|||||||
|
|
||||||
class CarHyundaiIoniq : public CarInterface {
|
class CarHyundaiIoniq : public CarInterface {
|
||||||
|
|
||||||
private:
|
protected:
|
||||||
|
|
||||||
public:
|
public:
|
||||||
void activateCommandQueue() override;
|
void activateCommandQueue() override;
|
||||||
|
|||||||
@@ -5,7 +5,7 @@
|
|||||||
#include "LiveData.h"
|
#include "LiveData.h"
|
||||||
|
|
||||||
void CarInterface::setLiveData(LiveData* pLiveData) {
|
void CarInterface::setLiveData(LiveData* pLiveData) {
|
||||||
this->liveData = pLiveData;
|
liveData = pLiveData;
|
||||||
}
|
}
|
||||||
|
|
||||||
void CarInterface::activateCommandQueue() {
|
void CarInterface::activateCommandQueue() {
|
||||||
|
|||||||
@@ -5,7 +5,7 @@
|
|||||||
|
|
||||||
class CarInterface {
|
class CarInterface {
|
||||||
|
|
||||||
private:
|
protected:
|
||||||
public:
|
public:
|
||||||
LiveData* liveData;
|
LiveData* liveData;
|
||||||
void setLiveData(LiveData* pLiveData);
|
void setLiveData(LiveData* pLiveData);
|
||||||
|
|||||||
@@ -219,18 +219,18 @@ void CarKiaDebugObd2::activateCommandQueue() {
|
|||||||
};
|
};
|
||||||
|
|
||||||
// 39 or 64 kWh model?
|
// 39 or 64 kWh model?
|
||||||
this->liveData->params.batteryTotalAvailableKWh = 64;
|
liveData->params.batteryTotalAvailableKWh = 64;
|
||||||
|
|
||||||
// Empty and fill command queue
|
// Empty and fill command queue
|
||||||
for (uint16_t i = 0; i < 300; i++) {
|
for (uint16_t i = 0; i < 300; i++) {
|
||||||
this->liveData->commandQueue[i] = "";
|
liveData->commandQueue[i] = "";
|
||||||
}
|
}
|
||||||
for (uint16_t i = 0; i < commandQueueCountDebugObd2Kia; i++) {
|
for (uint16_t i = 0; i < commandQueueCountDebugObd2Kia; i++) {
|
||||||
this->liveData->commandQueue[i] = commandQueueDebugObd2Kia[i];
|
liveData->commandQueue[i] = commandQueueDebugObd2Kia[i];
|
||||||
}
|
}
|
||||||
|
|
||||||
this->liveData->commandQueueLoopFrom = commandQueueLoopFromDebugObd2Kia;
|
liveData->commandQueueLoopFrom = commandQueueLoopFromDebugObd2Kia;
|
||||||
this->liveData->commandQueueCount = commandQueueCountDebugObd2Kia;
|
liveData->commandQueueCount = commandQueueCountDebugObd2Kia;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -239,142 +239,142 @@ void CarKiaDebugObd2::activateCommandQueue() {
|
|||||||
void CarKiaDebugObd2::parseRowMerged() {
|
void CarKiaDebugObd2::parseRowMerged() {
|
||||||
|
|
||||||
// VMCU 7E2
|
// VMCU 7E2
|
||||||
if (this->liveData->currentAtshRequest.equals("ATSH7E2")) {
|
if (liveData->currentAtshRequest.equals("ATSH7E2")) {
|
||||||
if (this->liveData->commandRequest.equals("2101")) {
|
if (liveData->commandRequest.equals("2101")) {
|
||||||
this->liveData->params.speedKmh = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(32, 36).c_str(), 2, false) * 0.0155; // / 100.0 *1.609 = real to gps is 1.750
|
liveData->params.speedKmh = liveData->hexToDecFromResponse(32, 36, 2, false) * 0.0155; // / 100.0 *1.609 = real to gps is 1.750
|
||||||
if (this->liveData->params.speedKmh < -99 || this->liveData->params.speedKmh > 200)
|
if (liveData->params.speedKmh < -99 || liveData->params.speedKmh > 200)
|
||||||
this->liveData->params.speedKmh = 0;
|
liveData->params.speedKmh = 0;
|
||||||
}
|
}
|
||||||
if (this->liveData->commandRequest.equals("2102")) {
|
if (liveData->commandRequest.equals("2102")) {
|
||||||
this->liveData->params.auxPerc = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(50, 52).c_str(), 1, false);
|
liveData->params.auxPerc = liveData->hexToDecFromResponse(50, 52, 1, false);
|
||||||
this->liveData->params.auxCurrentAmp = - this->liveData->hexToDec(this->liveData->responseRowMerged.substring(46, 50).c_str(), 2, true) / 1000.0;
|
liveData->params.auxCurrentAmp = - liveData->hexToDecFromResponse(46, 50, 2, true) / 1000.0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Cluster module 7c6
|
// Cluster module 7c6
|
||||||
if (this->liveData->currentAtshRequest.equals("ATSH7C6")) {
|
if (liveData->currentAtshRequest.equals("ATSH7C6")) {
|
||||||
if (this->liveData->commandRequest.equals("22B002")) {
|
if (liveData->commandRequest.equals("22B002")) {
|
||||||
this->liveData->params.odoKm = float(strtol(this->liveData->responseRowMerged.substring(18, 24).c_str(), 0, 16));
|
liveData->params.odoKm = liveData->decFromResponse(18, 24);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Aircon 7b3
|
// Aircon 7b3
|
||||||
if (this->liveData->currentAtshRequest.equals("ATSH7B3")) {
|
if (liveData->currentAtshRequest.equals("ATSH7B3")) {
|
||||||
if (this->liveData->commandRequest.equals("220100")) {
|
if (liveData->commandRequest.equals("220100")) {
|
||||||
this->liveData->params.indoorTemperature = (this->liveData->hexToDec(this->liveData->responseRowMerged.substring(16, 18).c_str(), 1, false) / 2) - 40;
|
liveData->params.indoorTemperature = (liveData->hexToDecFromResponse(16, 18, 1, false) / 2) - 40;
|
||||||
this->liveData->params.outdoorTemperature = (this->liveData->hexToDec(this->liveData->responseRowMerged.substring(18, 20).c_str(), 1, false) / 2) - 40;
|
liveData->params.outdoorTemperature = (liveData->hexToDecFromResponse(18, 20, 1, false) / 2) - 40;
|
||||||
}
|
}
|
||||||
if (this->liveData->commandRequest.equals("220102") && this->liveData->responseRowMerged.substring(12, 14) == "00") {
|
if (liveData->commandRequest.equals("220102") && liveData->responseRowMerged.substring(12, 14) == "00") {
|
||||||
this->liveData->params.coolantTemp1C = (this->liveData->hexToDec(this->liveData->responseRowMerged.substring(14, 16).c_str(), 1, false) / 2) - 40;
|
liveData->params.coolantTemp1C = (liveData->hexToDecFromResponse(14, 16, 1, false) / 2) - 40;
|
||||||
this->liveData->params.coolantTemp2C = (this->liveData->hexToDec(this->liveData->responseRowMerged.substring(16, 18).c_str(), 1, false) / 2) - 40;
|
liveData->params.coolantTemp2C = (liveData->hexToDecFromResponse(16, 18, 1, false) / 2) - 40;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// BMS 7e4
|
// BMS 7e4
|
||||||
if (this->liveData->currentAtshRequest.equals("ATSH7E4")) {
|
if (liveData->currentAtshRequest.equals("ATSH7E4")) {
|
||||||
if (this->liveData->commandRequest.equals("220101")) {
|
if (liveData->commandRequest.equals("220101")) {
|
||||||
this->liveData->params.cumulativeEnergyChargedKWh = float(strtol(this->liveData->responseRowMerged.substring(82, 90).c_str(), 0, 16)) / 10.0;
|
liveData->params.cumulativeEnergyChargedKWh = liveData->decFromResponse(82, 90) / 10.0;
|
||||||
if (this->liveData->params.cumulativeEnergyChargedKWhStart == -1)
|
if (liveData->params.cumulativeEnergyChargedKWhStart == -1)
|
||||||
this->liveData->params.cumulativeEnergyChargedKWhStart = this->liveData->params.cumulativeEnergyChargedKWh;
|
liveData->params.cumulativeEnergyChargedKWhStart = liveData->params.cumulativeEnergyChargedKWh;
|
||||||
this->liveData->params.cumulativeEnergyDischargedKWh = float(strtol(this->liveData->responseRowMerged.substring(90, 98).c_str(), 0, 16)) / 10.0;
|
liveData->params.cumulativeEnergyDischargedKWh = liveData->decFromResponse(90, 98) / 10.0;
|
||||||
if (this->liveData->params.cumulativeEnergyDischargedKWhStart == -1)
|
if (liveData->params.cumulativeEnergyDischargedKWhStart == -1)
|
||||||
this->liveData->params.cumulativeEnergyDischargedKWhStart = this->liveData->params.cumulativeEnergyDischargedKWh;
|
liveData->params.cumulativeEnergyDischargedKWhStart = liveData->params.cumulativeEnergyDischargedKWh;
|
||||||
this->liveData->params.auxVoltage = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(64, 66).c_str(), 2, true) / 10.0;
|
liveData->params.auxVoltage = liveData->hexToDecFromResponse(64, 66, 2, true) / 10.0;
|
||||||
this->liveData->params.batPowerAmp = - this->liveData->hexToDec(this->liveData->responseRowMerged.substring(26, 30).c_str(), 2, true) / 10.0;
|
liveData->params.batPowerAmp = - liveData->hexToDecFromResponse(26, 30, 2, true) / 10.0;
|
||||||
this->liveData->params.batVoltage = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(30, 34).c_str(), 2, false) / 10.0;
|
liveData->params.batVoltage = liveData->hexToDecFromResponse(30, 34, 2, false) / 10.0;
|
||||||
this->liveData->params.batPowerKw = (this->liveData->params.batPowerAmp * this->liveData->params.batVoltage) / 1000.0;
|
liveData->params.batPowerKw = (liveData->params.batPowerAmp * liveData->params.batVoltage) / 1000.0;
|
||||||
this->liveData->params.batPowerKwh100 = this->liveData->params.batPowerKw / this->liveData->params.speedKmh * 100;
|
liveData->params.batPowerKwh100 = liveData->params.batPowerKw / liveData->params.speedKmh * 100;
|
||||||
this->liveData->params.batCellMaxV = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(52, 54).c_str(), 1, false) / 50.0;
|
liveData->params.batCellMaxV = liveData->hexToDecFromResponse(52, 54, 1, false) / 50.0;
|
||||||
this->liveData->params.batCellMinV = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(56, 58).c_str(), 1, false) / 50.0;
|
liveData->params.batCellMinV = liveData->hexToDecFromResponse(56, 58, 1, false) / 50.0;
|
||||||
this->liveData->params.batModuleTempC[0] = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(38, 40).c_str(), 1, true);
|
liveData->params.batModuleTempC[0] = liveData->hexToDecFromResponse(38, 40, 1, true);
|
||||||
this->liveData->params.batModuleTempC[1] = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(40, 42).c_str(), 1, true);
|
liveData->params.batModuleTempC[1] = liveData->hexToDecFromResponse(40, 42, 1, true);
|
||||||
this->liveData->params.batModuleTempC[2] = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(42, 44).c_str(), 1, true);
|
liveData->params.batModuleTempC[2] = liveData->hexToDecFromResponse(42, 44, 1, true);
|
||||||
this->liveData->params.batModuleTempC[3] = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(44, 46).c_str(), 1, true);
|
liveData->params.batModuleTempC[3] = liveData->hexToDecFromResponse(44, 46, 1, true);
|
||||||
//this->liveData->params.batTempC = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(36, 38).c_str(), 1, true);
|
//liveData->params.batTempC = liveData->hexToDecFromResponse(36, 38, 1, true);
|
||||||
//this->liveData->params.batMaxC = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(34, 36).c_str(), 1, true);
|
//liveData->params.batMaxC = liveData->hexToDecFromResponse(34, 36, 1, true);
|
||||||
//this->liveData->params.batMinC = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(36, 38).c_str(), 1, true);
|
//liveData->params.batMinC = liveData->hexToDecFromResponse(36, 38, 1, true);
|
||||||
|
|
||||||
// This is more accurate than min/max from BMS. It's required to detect kona/eniro cold gates (min 15C is needed > 43kW charging, min 25C is needed > 58kW charging)
|
// This is more accurate than min/max from BMS. It's required to detect kona/eniro cold gates (min 15C is needed > 43kW charging, min 25C is needed > 58kW charging)
|
||||||
this->liveData->params.batMinC = this->liveData->params.batMaxC = this->liveData->params.batModuleTempC[0];
|
liveData->params.batMinC = liveData->params.batMaxC = liveData->params.batModuleTempC[0];
|
||||||
this->liveData->params.batMinC = (this->liveData->params.batModuleTempC[1] < this->liveData->params.batMinC) ? this->liveData->params.batModuleTempC[1] : this->liveData->params.batMinC;
|
liveData->params.batMinC = (liveData->params.batModuleTempC[1] < liveData->params.batMinC) ? liveData->params.batModuleTempC[1] : liveData->params.batMinC;
|
||||||
this->liveData->params.batMinC = (this->liveData->params.batModuleTempC[2] < this->liveData->params.batMinC) ? this->liveData->params.batModuleTempC[2] : this->liveData->params.batMinC;
|
liveData->params.batMinC = (liveData->params.batModuleTempC[2] < liveData->params.batMinC) ? liveData->params.batModuleTempC[2] : liveData->params.batMinC;
|
||||||
this->liveData->params.batMinC = (this->liveData->params.batModuleTempC[3] < this->liveData->params.batMinC) ? this->liveData->params.batModuleTempC[3] : this->liveData->params.batMinC;
|
liveData->params.batMinC = (liveData->params.batModuleTempC[3] < liveData->params.batMinC) ? liveData->params.batModuleTempC[3] : liveData->params.batMinC;
|
||||||
this->liveData->params.batMaxC = (this->liveData->params.batModuleTempC[1] > this->liveData->params.batMaxC) ? this->liveData->params.batModuleTempC[1] : this->liveData->params.batMaxC;
|
liveData->params.batMaxC = (liveData->params.batModuleTempC[1] > liveData->params.batMaxC) ? liveData->params.batModuleTempC[1] : liveData->params.batMaxC;
|
||||||
this->liveData->params.batMaxC = (this->liveData->params.batModuleTempC[2] > this->liveData->params.batMaxC) ? this->liveData->params.batModuleTempC[2] : this->liveData->params.batMaxC;
|
liveData->params.batMaxC = (liveData->params.batModuleTempC[2] > liveData->params.batMaxC) ? liveData->params.batModuleTempC[2] : liveData->params.batMaxC;
|
||||||
this->liveData->params.batMaxC = (this->liveData->params.batModuleTempC[3] > this->liveData->params.batMaxC) ? this->liveData->params.batModuleTempC[3] : this->liveData->params.batMaxC;
|
liveData->params.batMaxC = (liveData->params.batModuleTempC[3] > liveData->params.batMaxC) ? liveData->params.batModuleTempC[3] : liveData->params.batMaxC;
|
||||||
this->liveData->params.batTempC = this->liveData->params.batMinC;
|
liveData->params.batTempC = liveData->params.batMinC;
|
||||||
|
|
||||||
this->liveData->params.batInletC = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(50, 52).c_str(), 1, true);
|
liveData->params.batInletC = liveData->hexToDecFromResponse(50, 52, 1, true);
|
||||||
if (this->liveData->params.speedKmh < 10 && this->liveData->params.batPowerKw >= 1 && this->liveData->params.socPerc > 0 && this->liveData->params.socPerc <= 100) {
|
if (liveData->params.speedKmh < 10 && liveData->params.batPowerKw >= 1 && liveData->params.socPerc > 0 && liveData->params.socPerc <= 100) {
|
||||||
if ( this->liveData->params.chargingGraphMinKw[int(this->liveData->params.socPerc)] == -100 || this->liveData->params.batPowerKw < this->liveData->params.chargingGraphMinKw[int(this->liveData->params.socPerc)])
|
if ( liveData->params.chargingGraphMinKw[int(liveData->params.socPerc)] == -100 || liveData->params.batPowerKw < liveData->params.chargingGraphMinKw[int(liveData->params.socPerc)])
|
||||||
this->liveData->params.chargingGraphMinKw[int(this->liveData->params.socPerc)] = this->liveData->params.batPowerKw;
|
liveData->params.chargingGraphMinKw[int(liveData->params.socPerc)] = liveData->params.batPowerKw;
|
||||||
if ( this->liveData->params.chargingGraphMaxKw[int(this->liveData->params.socPerc)] == -100 || this->liveData->params.batPowerKw > this->liveData->params.chargingGraphMaxKw[int(this->liveData->params.socPerc)])
|
if ( liveData->params.chargingGraphMaxKw[int(liveData->params.socPerc)] == -100 || liveData->params.batPowerKw > liveData->params.chargingGraphMaxKw[int(liveData->params.socPerc)])
|
||||||
this->liveData->params.chargingGraphMaxKw[int(this->liveData->params.socPerc)] = this->liveData->params.batPowerKw;
|
liveData->params.chargingGraphMaxKw[int(liveData->params.socPerc)] = liveData->params.batPowerKw;
|
||||||
this->liveData->params.chargingGraphBatMinTempC[int(this->liveData->params.socPerc)] = this->liveData->params.batMinC;
|
liveData->params.chargingGraphBatMinTempC[int(liveData->params.socPerc)] = liveData->params.batMinC;
|
||||||
this->liveData->params.chargingGraphBatMaxTempC[int(this->liveData->params.socPerc)] = this->liveData->params.batMaxC;
|
liveData->params.chargingGraphBatMaxTempC[int(liveData->params.socPerc)] = liveData->params.batMaxC;
|
||||||
this->liveData->params.chargingGraphHeaterTempC[int(this->liveData->params.socPerc)] = this->liveData->params.batHeaterC;
|
liveData->params.chargingGraphHeaterTempC[int(liveData->params.socPerc)] = liveData->params.batHeaterC;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
// BMS 7e4
|
// BMS 7e4
|
||||||
if (this->liveData->commandRequest.equals("220102") && this->liveData->responseRowMerged.substring(12, 14) == "FF") {
|
if (liveData->commandRequest.equals("220102") && liveData->responseRowMerged.substring(12, 14) == "FF") {
|
||||||
for (int i = 0; i < 32; i++) {
|
for (int i = 0; i < 32; i++) {
|
||||||
this->liveData->params.cellVoltage[i] = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(14 + (i * 2), 14 + (i * 2) + 2).c_str(), 1, false) / 50;
|
liveData->params.cellVoltage[i] = liveData->hexToDecFromResponse(14 + (i * 2), 14 + (i * 2) + 2, 1, false) / 50;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
// BMS 7e4
|
// BMS 7e4
|
||||||
if (this->liveData->commandRequest.equals("220103")) {
|
if (liveData->commandRequest.equals("220103")) {
|
||||||
for (int i = 0; i < 32; i++) {
|
for (int i = 0; i < 32; i++) {
|
||||||
this->liveData->params.cellVoltage[32 + i] = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(14 + (i * 2), 14 + (i * 2) + 2).c_str(), 1, false) / 50;
|
liveData->params.cellVoltage[32 + i] = liveData->hexToDecFromResponse(14 + (i * 2), 14 + (i * 2) + 2, 1, false) / 50;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
// BMS 7e4
|
// BMS 7e4
|
||||||
if (this->liveData->commandRequest.equals("220104")) {
|
if (liveData->commandRequest.equals("220104")) {
|
||||||
for (int i = 0; i < 32; i++) {
|
for (int i = 0; i < 32; i++) {
|
||||||
this->liveData->params.cellVoltage[64 + i] = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(14 + (i * 2), 14 + (i * 2) + 2).c_str(), 1, false) / 50;
|
liveData->params.cellVoltage[64 + i] = liveData->hexToDecFromResponse(14 + (i * 2), 14 + (i * 2) + 2, 1, false) / 50;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
// BMS 7e4
|
// BMS 7e4
|
||||||
if (this->liveData->commandRequest.equals("220105")) {
|
if (liveData->commandRequest.equals("220105")) {
|
||||||
this->liveData->params.socPercPrevious = this->liveData->params.socPerc;
|
liveData->params.socPercPrevious = liveData->params.socPerc;
|
||||||
this->liveData->params.sohPerc = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(56, 60).c_str(), 2, false) / 10.0;
|
liveData->params.sohPerc = liveData->hexToDecFromResponse(56, 60, 2, false) / 10.0;
|
||||||
this->liveData->params.socPerc = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(68, 70).c_str(), 1, false) / 2.0;
|
liveData->params.socPerc = liveData->hexToDecFromResponse(68, 70, 1, false) / 2.0;
|
||||||
|
|
||||||
// Soc10ced table, record x0% CEC/CED table (ex. 90%->89%, 80%->79%)
|
// Soc10ced table, record x0% CEC/CED table (ex. 90%->89%, 80%->79%)
|
||||||
if (this->liveData->params.socPercPrevious - this->liveData->params.socPerc > 0) {
|
if (liveData->params.socPercPrevious - liveData->params.socPerc > 0) {
|
||||||
byte index = (int(this->liveData->params.socPerc) == 4) ? 0 : (int)(this->liveData->params.socPerc / 10) + 1;
|
byte index = (int(liveData->params.socPerc) == 4) ? 0 : (int)(liveData->params.socPerc / 10) + 1;
|
||||||
if ((int(this->liveData->params.socPerc) % 10 == 9 || int(this->liveData->params.socPerc) == 4) && this->liveData->params.soc10ced[index] == -1) {
|
if ((int(liveData->params.socPerc) % 10 == 9 || int(liveData->params.socPerc) == 4) && liveData->params.soc10ced[index] == -1) {
|
||||||
struct tm now;
|
struct tm now;
|
||||||
getLocalTime(&now, 0);
|
getLocalTime(&now, 0);
|
||||||
time_t time_now_epoch = mktime(&now);
|
time_t time_now_epoch = mktime(&now);
|
||||||
this->liveData->params.soc10ced[index] = this->liveData->params.cumulativeEnergyDischargedKWh;
|
liveData->params.soc10ced[index] = liveData->params.cumulativeEnergyDischargedKWh;
|
||||||
this->liveData->params.soc10cec[index] = this->liveData->params.cumulativeEnergyChargedKWh;
|
liveData->params.soc10cec[index] = liveData->params.cumulativeEnergyChargedKWh;
|
||||||
this->liveData->params.soc10odo[index] = this->liveData->params.odoKm;
|
liveData->params.soc10odo[index] = liveData->params.odoKm;
|
||||||
this->liveData->params.soc10time[index] = time_now_epoch;
|
liveData->params.soc10time[index] = time_now_epoch;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
this->liveData->params.batHeaterC = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(52, 54).c_str(), 1, true);
|
liveData->params.batHeaterC = liveData->hexToDecFromResponse(52, 54, 1, true);
|
||||||
//
|
//
|
||||||
for (int i = 30; i < 32; i++) { // ai/aj position
|
for (int i = 30; i < 32; i++) { // ai/aj position
|
||||||
this->liveData->params.cellVoltage[96 - 30 + i] = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(14 + (i * 2), 14 + (i * 2) + 2).c_str(), 1, false) / 50;
|
liveData->params.cellVoltage[96 - 30 + i] = liveData->hexToDecFromResponse(14 + (i * 2), 14 + (i * 2) + 2, 1, false) / 50;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
// BMS 7e4
|
// BMS 7e4
|
||||||
if (this->liveData->commandRequest.equals("220106")) {
|
if (liveData->commandRequest.equals("220106")) {
|
||||||
this->liveData->params.coolingWaterTempC = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(14, 16).c_str(), 1, false);
|
liveData->params.coolingWaterTempC = liveData->hexToDecFromResponse(14, 16, 1, false);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// TPMS 7a0
|
// TPMS 7a0
|
||||||
if (this->liveData->currentAtshRequest.equals("ATSH7A0")) {
|
if (liveData->currentAtshRequest.equals("ATSH7A0")) {
|
||||||
if (this->liveData->commandRequest.equals("22c00b")) {
|
if (liveData->commandRequest.equals("22c00b")) {
|
||||||
this->liveData->params.tireFrontLeftPressureBar = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(14, 16).c_str(), 2, false) / 72.51886900361; // === OK Valid *0.2 / 14.503773800722
|
liveData->params.tireFrontLeftPressureBar = liveData->hexToDecFromResponse(14, 16, 2, false) / 72.51886900361; // === OK Valid *0.2 / 14.503773800722
|
||||||
this->liveData->params.tireFrontRightPressureBar = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(22, 24).c_str(), 2, false) / 72.51886900361; // === OK Valid *0.2 / 14.503773800722
|
liveData->params.tireFrontRightPressureBar = liveData->hexToDecFromResponse(22, 24, 2, false) / 72.51886900361; // === OK Valid *0.2 / 14.503773800722
|
||||||
this->liveData->params.tireRearRightPressureBar = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(30, 32).c_str(), 2, false) / 72.51886900361; // === OK Valid *0.2 / 14.503773800722
|
liveData->params.tireRearRightPressureBar = liveData->hexToDecFromResponse(30, 32, 2, false) / 72.51886900361; // === OK Valid *0.2 / 14.503773800722
|
||||||
this->liveData->params.tireRearLeftPressureBar = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(38, 40).c_str(), 2, false) / 72.51886900361; // === OK Valid *0.2 / 14.503773800722
|
liveData->params.tireRearLeftPressureBar = liveData->hexToDecFromResponse(38, 40, 2, false) / 72.51886900361; // === OK Valid *0.2 / 14.503773800722
|
||||||
this->liveData->params.tireFrontLeftTempC = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(16, 18).c_str(), 2, false) - 50; // === OK Valid
|
liveData->params.tireFrontLeftTempC = liveData->hexToDecFromResponse(16, 18, 2, false) - 50; // === OK Valid
|
||||||
this->liveData->params.tireFrontRightTempC = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(24, 26).c_str(), 2, false) - 50; // === OK Valid
|
liveData->params.tireFrontRightTempC = liveData->hexToDecFromResponse(24, 26, 2, false) - 50; // === OK Valid
|
||||||
this->liveData->params.tireRearRightTempC = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(32, 34).c_str(), 2, false) - 50; // === OK Valid
|
liveData->params.tireRearRightTempC = liveData->hexToDecFromResponse(32, 34, 2, false) - 50; // === OK Valid
|
||||||
this->liveData->params.tireRearLeftTempC = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(40, 42).c_str(), 2, false) - 50; // === OK Valid
|
liveData->params.tireRearLeftTempC = liveData->hexToDecFromResponse(40, 42, 2, false) - 50; // === OK Valid
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -386,134 +386,134 @@ void CarKiaDebugObd2::parseRowMerged() {
|
|||||||
void CarKiaDebugObd2::loadTestData() {
|
void CarKiaDebugObd2::loadTestData() {
|
||||||
|
|
||||||
// VMCU ATSH7E2
|
// VMCU ATSH7E2
|
||||||
this->liveData->currentAtshRequest = "ATSH7E2";
|
liveData->currentAtshRequest = "ATSH7E2";
|
||||||
// 2101
|
// 2101
|
||||||
this->liveData->commandRequest = "2101";
|
liveData->commandRequest = "2101";
|
||||||
this->liveData->responseRowMerged = "6101FFF8000009285A3B0648030000B4179D763404080805000000";
|
liveData->responseRowMerged = "6101FFF8000009285A3B0648030000B4179D763404080805000000";
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
// 2102
|
// 2102
|
||||||
this->liveData->commandRequest = "2102";
|
liveData->commandRequest = "2102";
|
||||||
this->liveData->responseRowMerged = "6102F8FFFC000101000000840FBF83BD33270680953033757F59291C76000001010100000007000000";
|
liveData->responseRowMerged = "6102F8FFFC000101000000840FBF83BD33270680953033757F59291C76000001010100000007000000";
|
||||||
this->liveData->responseRowMerged = "6102F8FFFC000101000000931CC77F4C39040BE09BA7385D8158832175000001010100000007000000";
|
liveData->responseRowMerged = "6102F8FFFC000101000000931CC77F4C39040BE09BA7385D8158832175000001010100000007000000";
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
|
|
||||||
// "ATSH7DF",
|
// "ATSH7DF",
|
||||||
this->liveData->currentAtshRequest = "ATSH7DF";
|
liveData->currentAtshRequest = "ATSH7DF";
|
||||||
// 2106
|
// 2106
|
||||||
this->liveData->commandRequest = "2106";
|
liveData->commandRequest = "2106";
|
||||||
this->liveData->responseRowMerged = "6106FFFF800000000000000200001B001C001C000600060006000E000000010000000000000000013D013D013E013E00";
|
liveData->responseRowMerged = "6106FFFF800000000000000200001B001C001C000600060006000E000000010000000000000000013D013D013E013E00";
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
|
|
||||||
// AIRCON / ACU ATSH7B3
|
// AIRCON / ACU ATSH7B3
|
||||||
this->liveData->currentAtshRequest = "ATSH7B3";
|
liveData->currentAtshRequest = "ATSH7B3";
|
||||||
// 220100
|
// 220100
|
||||||
this->liveData->commandRequest = "220100";
|
liveData->commandRequest = "220100";
|
||||||
this->liveData->responseRowMerged = "6201007E5027C8FF7F765D05B95AFFFF5AFF11FFFFFFFFFFFF6AFFFF2DF0757630FFFF00FFFF000000";
|
liveData->responseRowMerged = "6201007E5027C8FF7F765D05B95AFFFF5AFF11FFFFFFFFFFFF6AFFFF2DF0757630FFFF00FFFF000000";
|
||||||
this->liveData->responseRowMerged = "6201007E5027C8FF867C58121010FFFF10FF8EFFFFFFFFFFFF10FFFF0DF0617900FFFF01FFFF000000";
|
liveData->responseRowMerged = "6201007E5027C8FF867C58121010FFFF10FF8EFFFFFFFFFFFF10FFFF0DF0617900FFFF01FFFF000000";
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
|
|
||||||
// BMS ATSH7E4
|
// BMS ATSH7E4
|
||||||
this->liveData->currentAtshRequest = "ATSH7E4";
|
liveData->currentAtshRequest = "ATSH7E4";
|
||||||
// 220101
|
// 220101
|
||||||
this->liveData->commandRequest = "220101";
|
liveData->commandRequest = "220101";
|
||||||
this->liveData->responseRowMerged = "620101FFF7E7FF99000000000300B10EFE120F11100F12000018C438C30B00008400003864000035850000153A00001374000647010D017F0BDA0BDA03E8";
|
liveData->responseRowMerged = "620101FFF7E7FF99000000000300B10EFE120F11100F12000018C438C30B00008400003864000035850000153A00001374000647010D017F0BDA0BDA03E8";
|
||||||
this->liveData->responseRowMerged = "620101FFF7E7FFB3000000000300120F9B111011101011000014CC38CB3B00009100003A510000367C000015FB000013D3000690250D018E0000000003E8";
|
liveData->responseRowMerged = "620101FFF7E7FFB3000000000300120F9B111011101011000014CC38CB3B00009100003A510000367C000015FB000013D3000690250D018E0000000003E8";
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
// 220102
|
// 220102
|
||||||
this->liveData->commandRequest = "220102";
|
liveData->commandRequest = "220102";
|
||||||
this->liveData->responseRowMerged = "620102FFFFFFFFCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBAAAA";
|
liveData->responseRowMerged = "620102FFFFFFFFCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBAAAA";
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
// 220103
|
// 220103
|
||||||
this->liveData->commandRequest = "220103";
|
liveData->commandRequest = "220103";
|
||||||
this->liveData->responseRowMerged = "620103FFFFFFFFCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCACBCACACFCCCBCBCBCBCBCBCBCBAAAA";
|
liveData->responseRowMerged = "620103FFFFFFFFCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCACBCACACFCCCBCBCBCBCBCBCBCBAAAA";
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
// 220104
|
// 220104
|
||||||
this->liveData->commandRequest = "220104";
|
liveData->commandRequest = "220104";
|
||||||
this->liveData->responseRowMerged = "620104FFFFFFFFCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBAAAA";
|
liveData->responseRowMerged = "620104FFFFFFFFCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBAAAA";
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
// 220105
|
// 220105
|
||||||
this->liveData->commandRequest = "220105";
|
liveData->commandRequest = "220105";
|
||||||
this->liveData->responseRowMerged = "620105003fff9000000000000000000F8A86012B4946500101500DAC03E800000000AC0000C7C701000F00000000AAAA";
|
liveData->responseRowMerged = "620105003fff9000000000000000000F8A86012B4946500101500DAC03E800000000AC0000C7C701000F00000000AAAA";
|
||||||
this->liveData->responseRowMerged = "620105003FFF90000000000000000014918E012927465000015013BB03E800000000BB0000CBCB01001300000000AAAA";
|
liveData->responseRowMerged = "620105003FFF90000000000000000014918E012927465000015013BB03E800000000BB0000CBCB01001300000000AAAA";
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
// 220106
|
// 220106
|
||||||
this->liveData->commandRequest = "220106";
|
liveData->commandRequest = "220106";
|
||||||
this->liveData->responseRowMerged = "620106FFFFFFFF14001A00240000003A7C86B4B30000000928EA00";
|
liveData->responseRowMerged = "620106FFFFFFFF14001A00240000003A7C86B4B30000000928EA00";
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
|
|
||||||
// BCM / TPMS ATSH7A0
|
// BCM / TPMS ATSH7A0
|
||||||
this->liveData->currentAtshRequest = "ATSH7A0";
|
liveData->currentAtshRequest = "ATSH7A0";
|
||||||
// 22c00b
|
// 22c00b
|
||||||
this->liveData->commandRequest = "22c00b";
|
liveData->commandRequest = "22c00b";
|
||||||
this->liveData->responseRowMerged = "62C00BFFFF0000B93D0100B43E0100B43D0100BB3C0100AAAAAAAA";
|
liveData->responseRowMerged = "62C00BFFFF0000B93D0100B43E0100B43D0100BB3C0100AAAAAAAA";
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
|
|
||||||
// ATSH7C6
|
// ATSH7C6
|
||||||
this->liveData->currentAtshRequest = "ATSH7C6";
|
liveData->currentAtshRequest = "ATSH7C6";
|
||||||
// 22b002
|
// 22b002
|
||||||
this->liveData->commandRequest = "22b002";
|
liveData->commandRequest = "22b002";
|
||||||
this->liveData->responseRowMerged = "62B002E0000000FFB400330B0000000000000000";
|
liveData->responseRowMerged = "62B002E0000000FFB400330B0000000000000000";
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
|
|
||||||
this->liveData->params.batModuleTempC[0] = 28;
|
liveData->params.batModuleTempC[0] = 28;
|
||||||
this->liveData->params.batModuleTempC[1] = 29;
|
liveData->params.batModuleTempC[1] = 29;
|
||||||
this->liveData->params.batModuleTempC[2] = 28;
|
liveData->params.batModuleTempC[2] = 28;
|
||||||
this->liveData->params.batModuleTempC[3] = 30;
|
liveData->params.batModuleTempC[3] = 30;
|
||||||
// This is more accurate than min/max from BMS. It's required to detect kona/eniro cold gates (min 15C is needed > 43kW charging, min 25C is needed > 58kW charging)
|
// This is more accurate than min/max from BMS. It's required to detect kona/eniro cold gates (min 15C is needed > 43kW charging, min 25C is needed > 58kW charging)
|
||||||
this->liveData->params.batMinC = this->liveData->params.batMaxC = this->liveData->params.batModuleTempC[0];
|
liveData->params.batMinC = liveData->params.batMaxC = liveData->params.batModuleTempC[0];
|
||||||
for (uint16_t i = 1; i < this->liveData->params.batModuleTempCount; i++) {
|
for (uint16_t i = 1; i < liveData->params.batModuleTempCount; i++) {
|
||||||
if (this->liveData->params.batModuleTempC[i] < this->liveData->params.batMinC)
|
if (liveData->params.batModuleTempC[i] < liveData->params.batMinC)
|
||||||
this->liveData->params.batMinC = this->liveData->params.batModuleTempC[i];
|
liveData->params.batMinC = liveData->params.batModuleTempC[i];
|
||||||
if (this->liveData->params.batModuleTempC[i] > this->liveData->params.batMaxC)
|
if (liveData->params.batModuleTempC[i] > liveData->params.batMaxC)
|
||||||
this->liveData->params.batMaxC = this->liveData->params.batModuleTempC[i];
|
liveData->params.batMaxC = liveData->params.batModuleTempC[i];
|
||||||
}
|
}
|
||||||
this->liveData->params.batTempC = this->liveData->params.batMinC;
|
liveData->params.batTempC = liveData->params.batMinC;
|
||||||
|
|
||||||
//
|
//
|
||||||
this->liveData->params.soc10ced[10] = 2200;
|
liveData->params.soc10ced[10] = 2200;
|
||||||
this->liveData->params.soc10cec[10] = 2500;
|
liveData->params.soc10cec[10] = 2500;
|
||||||
this->liveData->params.soc10odo[10] = 13000;
|
liveData->params.soc10odo[10] = 13000;
|
||||||
this->liveData->params.soc10time[10] = 13000;
|
liveData->params.soc10time[10] = 13000;
|
||||||
this->liveData->params.soc10ced[9] = this->liveData->params.soc10ced[10] + 6.4;
|
liveData->params.soc10ced[9] = liveData->params.soc10ced[10] + 6.4;
|
||||||
this->liveData->params.soc10cec[9] = this->liveData->params.soc10cec[10] + 0;
|
liveData->params.soc10cec[9] = liveData->params.soc10cec[10] + 0;
|
||||||
this->liveData->params.soc10odo[9] = this->liveData->params.soc10odo[10] + 30;
|
liveData->params.soc10odo[9] = liveData->params.soc10odo[10] + 30;
|
||||||
this->liveData->params.soc10time[9] = this->liveData->params.soc10time[10] + 900;
|
liveData->params.soc10time[9] = liveData->params.soc10time[10] + 900;
|
||||||
this->liveData->params.soc10ced[8] = this->liveData->params.soc10ced[9] + 6.8;
|
liveData->params.soc10ced[8] = liveData->params.soc10ced[9] + 6.8;
|
||||||
this->liveData->params.soc10cec[8] = this->liveData->params.soc10cec[9] + 0;
|
liveData->params.soc10cec[8] = liveData->params.soc10cec[9] + 0;
|
||||||
this->liveData->params.soc10odo[8] = this->liveData->params.soc10odo[9] + 30;
|
liveData->params.soc10odo[8] = liveData->params.soc10odo[9] + 30;
|
||||||
this->liveData->params.soc10time[8] = this->liveData->params.soc10time[9] + 900;
|
liveData->params.soc10time[8] = liveData->params.soc10time[9] + 900;
|
||||||
this->liveData->params.soc10ced[7] = this->liveData->params.soc10ced[8] + 7.2;
|
liveData->params.soc10ced[7] = liveData->params.soc10ced[8] + 7.2;
|
||||||
this->liveData->params.soc10cec[7] = this->liveData->params.soc10cec[8] + 0.6;
|
liveData->params.soc10cec[7] = liveData->params.soc10cec[8] + 0.6;
|
||||||
this->liveData->params.soc10odo[7] = this->liveData->params.soc10odo[8] + 30;
|
liveData->params.soc10odo[7] = liveData->params.soc10odo[8] + 30;
|
||||||
this->liveData->params.soc10time[7] = this->liveData->params.soc10time[8] + 900;
|
liveData->params.soc10time[7] = liveData->params.soc10time[8] + 900;
|
||||||
this->liveData->params.soc10ced[6] = this->liveData->params.soc10ced[7] + 6.7;
|
liveData->params.soc10ced[6] = liveData->params.soc10ced[7] + 6.7;
|
||||||
this->liveData->params.soc10cec[6] = this->liveData->params.soc10cec[7] + 0;
|
liveData->params.soc10cec[6] = liveData->params.soc10cec[7] + 0;
|
||||||
this->liveData->params.soc10odo[6] = this->liveData->params.soc10odo[7] + 30;
|
liveData->params.soc10odo[6] = liveData->params.soc10odo[7] + 30;
|
||||||
this->liveData->params.soc10time[6] = this->liveData->params.soc10time[7] + 900;
|
liveData->params.soc10time[6] = liveData->params.soc10time[7] + 900;
|
||||||
this->liveData->params.soc10ced[5] = this->liveData->params.soc10ced[6] + 6.7;
|
liveData->params.soc10ced[5] = liveData->params.soc10ced[6] + 6.7;
|
||||||
this->liveData->params.soc10cec[5] = this->liveData->params.soc10cec[6] + 0;
|
liveData->params.soc10cec[5] = liveData->params.soc10cec[6] + 0;
|
||||||
this->liveData->params.soc10odo[5] = this->liveData->params.soc10odo[6] + 30;
|
liveData->params.soc10odo[5] = liveData->params.soc10odo[6] + 30;
|
||||||
this->liveData->params.soc10time[5] = this->liveData->params.soc10time[6] + 900;
|
liveData->params.soc10time[5] = liveData->params.soc10time[6] + 900;
|
||||||
this->liveData->params.soc10ced[4] = this->liveData->params.soc10ced[5] + 6.4;
|
liveData->params.soc10ced[4] = liveData->params.soc10ced[5] + 6.4;
|
||||||
this->liveData->params.soc10cec[4] = this->liveData->params.soc10cec[5] + 0.3;
|
liveData->params.soc10cec[4] = liveData->params.soc10cec[5] + 0.3;
|
||||||
this->liveData->params.soc10odo[4] = this->liveData->params.soc10odo[5] + 30;
|
liveData->params.soc10odo[4] = liveData->params.soc10odo[5] + 30;
|
||||||
this->liveData->params.soc10time[4] = this->liveData->params.soc10time[5] + 900;
|
liveData->params.soc10time[4] = liveData->params.soc10time[5] + 900;
|
||||||
this->liveData->params.soc10ced[3] = this->liveData->params.soc10ced[4] + 6.4;
|
liveData->params.soc10ced[3] = liveData->params.soc10ced[4] + 6.4;
|
||||||
this->liveData->params.soc10cec[3] = this->liveData->params.soc10cec[4] + 0;
|
liveData->params.soc10cec[3] = liveData->params.soc10cec[4] + 0;
|
||||||
this->liveData->params.soc10odo[3] = this->liveData->params.soc10odo[4] + 30;
|
liveData->params.soc10odo[3] = liveData->params.soc10odo[4] + 30;
|
||||||
this->liveData->params.soc10time[3] = this->liveData->params.soc10time[4] + 900;
|
liveData->params.soc10time[3] = liveData->params.soc10time[4] + 900;
|
||||||
this->liveData->params.soc10ced[2] = this->liveData->params.soc10ced[3] + 5.4;
|
liveData->params.soc10ced[2] = liveData->params.soc10ced[3] + 5.4;
|
||||||
this->liveData->params.soc10cec[2] = this->liveData->params.soc10cec[3] + 0.1;
|
liveData->params.soc10cec[2] = liveData->params.soc10cec[3] + 0.1;
|
||||||
this->liveData->params.soc10odo[2] = this->liveData->params.soc10odo[3] + 30;
|
liveData->params.soc10odo[2] = liveData->params.soc10odo[3] + 30;
|
||||||
this->liveData->params.soc10time[2] = this->liveData->params.soc10time[3] + 900;
|
liveData->params.soc10time[2] = liveData->params.soc10time[3] + 900;
|
||||||
this->liveData->params.soc10ced[1] = this->liveData->params.soc10ced[2] + 6.2;
|
liveData->params.soc10ced[1] = liveData->params.soc10ced[2] + 6.2;
|
||||||
this->liveData->params.soc10cec[1] = this->liveData->params.soc10cec[2] + 0.1;
|
liveData->params.soc10cec[1] = liveData->params.soc10cec[2] + 0.1;
|
||||||
this->liveData->params.soc10odo[1] = this->liveData->params.soc10odo[2] + 30;
|
liveData->params.soc10odo[1] = liveData->params.soc10odo[2] + 30;
|
||||||
this->liveData->params.soc10time[1] = this->liveData->params.soc10time[2] + 900;
|
liveData->params.soc10time[1] = liveData->params.soc10time[2] + 900;
|
||||||
this->liveData->params.soc10ced[0] = this->liveData->params.soc10ced[1] + 2.9;
|
liveData->params.soc10ced[0] = liveData->params.soc10ced[1] + 2.9;
|
||||||
this->liveData->params.soc10cec[0] = this->liveData->params.soc10cec[1] + 0.5;
|
liveData->params.soc10cec[0] = liveData->params.soc10cec[1] + 0.5;
|
||||||
this->liveData->params.soc10odo[0] = this->liveData->params.soc10odo[1] + 15;
|
liveData->params.soc10odo[0] = liveData->params.soc10odo[1] + 15;
|
||||||
this->liveData->params.soc10time[0] = this->liveData->params.soc10time[1] + 900;
|
liveData->params.soc10time[0] = liveData->params.soc10time[1] + 900;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -5,7 +5,7 @@
|
|||||||
|
|
||||||
class CarKiaDebugObd2 : public CarInterface {
|
class CarKiaDebugObd2 : public CarInterface {
|
||||||
|
|
||||||
private:
|
protected:
|
||||||
|
|
||||||
public:
|
public:
|
||||||
void activateCommandQueue() override;
|
void activateCommandQueue() override;
|
||||||
|
|||||||
486
CarKiaEniro.cpp
486
CarKiaEniro.cpp
@@ -14,7 +14,7 @@
|
|||||||
#include <Arduino.h>
|
#include <Arduino.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include <WString.h>
|
#include <WString.h>
|
||||||
#include <String.h>
|
#include <string.h>
|
||||||
#include <sys/time.h>
|
#include <sys/time.h>
|
||||||
#include "LiveData.h"
|
#include "LiveData.h"
|
||||||
#include "CarKiaEniro.h"
|
#include "CarKiaEniro.h"
|
||||||
@@ -84,23 +84,23 @@ void CarKiaEniro::activateCommandQueue() {
|
|||||||
};
|
};
|
||||||
|
|
||||||
// 39 or 64 kWh model?
|
// 39 or 64 kWh model?
|
||||||
this->liveData->params.batModuleTempCount = 4;
|
liveData->params.batModuleTempCount = 4;
|
||||||
this->liveData->params.batteryTotalAvailableKWh = 64;
|
liveData->params.batteryTotalAvailableKWh = 64;
|
||||||
// =(I18*0,615)*(1+(I18*0,0008)) soc to kwh niro ev 2020
|
// =(I18*0,615)*(1+(I18*0,0008)) soc to kwh niro ev 2020
|
||||||
if (this->liveData->settings.carType == CAR_KIA_ENIRO_2020_39 || this->liveData->settings.carType == CAR_HYUNDAI_KONA_2020_39) {
|
if (liveData->settings.carType == CAR_KIA_ENIRO_2020_39 || liveData->settings.carType == CAR_HYUNDAI_KONA_2020_39) {
|
||||||
this->liveData->params.batteryTotalAvailableKWh = 39.2;
|
liveData->params.batteryTotalAvailableKWh = 39.2;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Empty and fill command queue
|
// Empty and fill command queue
|
||||||
for (int i = 0; i < 300; i++) {
|
for (int i = 0; i < 300; i++) {
|
||||||
this->liveData->commandQueue[i] = "";
|
liveData->commandQueue[i] = "";
|
||||||
}
|
}
|
||||||
for (int i = 0; i < commandQueueCountKiaENiro; i++) {
|
for (int i = 0; i < commandQueueCountKiaENiro; i++) {
|
||||||
this->liveData->commandQueue[i] = commandQueueKiaENiro[i];
|
liveData->commandQueue[i] = commandQueueKiaENiro[i];
|
||||||
}
|
}
|
||||||
|
|
||||||
this->liveData->commandQueueLoopFrom = commandQueueLoopFromKiaENiro;
|
liveData->commandQueueLoopFrom = commandQueueLoopFromKiaENiro;
|
||||||
this->liveData->commandQueueCount = commandQueueCountKiaENiro;
|
liveData->commandQueueCount = commandQueueCountKiaENiro;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -109,183 +109,195 @@ void CarKiaEniro::activateCommandQueue() {
|
|||||||
void CarKiaEniro::parseRowMerged() {
|
void CarKiaEniro::parseRowMerged() {
|
||||||
|
|
||||||
bool tempByte;
|
bool tempByte;
|
||||||
|
float tempFloat;
|
||||||
|
String tmpStr;
|
||||||
|
|
||||||
// ABS / ESP + AHB 7D1
|
// ABS / ESP + AHB 7D1
|
||||||
if (this->liveData->currentAtshRequest.equals("ATSH7D1")) {
|
if (liveData->currentAtshRequest.equals("ATSH7D1")) {
|
||||||
if (this->liveData->commandRequest.equals("22C101")) {
|
if (liveData->commandRequest.equals("22C101")) {
|
||||||
uint8_t driveMode = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(22, 24).c_str(), 1, false);
|
uint8_t driveMode = liveData->hexToDecFromResponse(22, 24, 1, false);
|
||||||
this->liveData->params.forwardDriveMode = (driveMode == 4);
|
liveData->params.forwardDriveMode = (driveMode == 4);
|
||||||
this->liveData->params.reverseDriveMode = (driveMode == 2);
|
liveData->params.reverseDriveMode = (driveMode == 2);
|
||||||
this->liveData->params.parkModeOrNeutral = (driveMode == 1);
|
liveData->params.parkModeOrNeutral = (driveMode == 1);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// IGPM
|
// IGPM
|
||||||
if (this->liveData->currentAtshRequest.equals("ATSH770")) {
|
if (liveData->currentAtshRequest.equals("ATSH770")) {
|
||||||
if (this->liveData->commandRequest.equals("22BC03")) {
|
if (liveData->commandRequest.equals("22BC03")) {
|
||||||
tempByte = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(16, 18).c_str(), 1, false);
|
tempByte = liveData->hexToDecFromResponse(16, 18, 1, false);
|
||||||
this->liveData->params.ignitionOnPrevious = this->liveData->params.ignitionOn;
|
liveData->params.ignitionOnPrevious = liveData->params.ignitionOn;
|
||||||
this->liveData->params.ignitionOn = (bitRead(tempByte, 5) == 1);
|
liveData->params.ignitionOn = (bitRead(tempByte, 5) == 1);
|
||||||
if (this->liveData->params.ignitionOnPrevious && !this->liveData->params.ignitionOn)
|
if (liveData->params.ignitionOnPrevious && !liveData->params.ignitionOn)
|
||||||
this->liveData->params.automaticShutdownTimer = this->liveData->params.currentTime;
|
liveData->params.automaticShutdownTimer = liveData->params.currentTime;
|
||||||
|
|
||||||
this->liveData->params.lightInfo = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(18, 20).c_str(), 1, false);
|
liveData->params.lightInfo = liveData->hexToDecFromResponse(18, 20, 1, false);
|
||||||
this->liveData->params.headLights = (bitRead(this->liveData->params.lightInfo, 5) == 1);
|
liveData->params.headLights = (bitRead(liveData->params.lightInfo, 5) == 1);
|
||||||
this->liveData->params.dayLights = (bitRead(this->liveData->params.lightInfo, 3) == 1);
|
liveData->params.dayLights = (bitRead(liveData->params.lightInfo, 3) == 1);
|
||||||
}
|
}
|
||||||
if (this->liveData->commandRequest.equals("22BC06")) {
|
if (liveData->commandRequest.equals("22BC06")) {
|
||||||
this->liveData->params.brakeLightInfo = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(14, 16).c_str(), 1, false);
|
liveData->params.brakeLightInfo = liveData->hexToDecFromResponse(14, 16, 1, false);
|
||||||
this->liveData->params.brakeLights = (bitRead(this->liveData->params.brakeLightInfo, 5) == 1);
|
liveData->params.brakeLights = (bitRead(liveData->params.brakeLightInfo, 5) == 1);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// VMCU 7E2
|
// VMCU 7E2
|
||||||
if (this->liveData->currentAtshRequest.equals("ATSH7E2")) {
|
if (liveData->currentAtshRequest.equals("ATSH7E2")) {
|
||||||
if (this->liveData->commandRequest.equals("2101")) {
|
if (liveData->commandRequest.equals("2101")) {
|
||||||
this->liveData->params.speedKmh = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(32, 36).c_str(), 2, false) * 0.0155; // / 100.0 *1.609 = real to gps is 1.750
|
liveData->params.speedKmh = liveData->hexToDecFromResponse(32, 36, 2, false) * 0.0155; // / 100.0 *1.609 = real to gps is 1.750
|
||||||
if (this->liveData->params.speedKmh < -99 || this->liveData->params.speedKmh > 200)
|
if (liveData->params.speedKmh < -99 || liveData->params.speedKmh > 200)
|
||||||
this->liveData->params.speedKmh = 0;
|
liveData->params.speedKmh = 0;
|
||||||
}
|
}
|
||||||
if (this->liveData->commandRequest.equals("2102")) {
|
if (liveData->commandRequest.equals("2102")) {
|
||||||
this->liveData->params.auxPerc = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(50, 52).c_str(), 1, false);
|
liveData->params.auxPerc = liveData->hexToDecFromResponse(50, 52, 1, false);
|
||||||
this->liveData->params.auxCurrentAmp = - this->liveData->hexToDec(this->liveData->responseRowMerged.substring(46, 50).c_str(), 2, true) / 1000.0;
|
liveData->params.auxCurrentAmp = - liveData->hexToDecFromResponse(46, 50, 2, true) / 1000.0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Cluster module 7c6
|
// Cluster module 7c6
|
||||||
if (this->liveData->currentAtshRequest.equals("ATSH7C6")) {
|
if (liveData->currentAtshRequest.equals("ATSH7C6")) {
|
||||||
if (this->liveData->commandRequest.equals("22B002")) {
|
if (liveData->commandRequest.equals("22B002")) {
|
||||||
this->liveData->params.odoKm = float(strtol(this->liveData->responseRowMerged.substring(18, 24).c_str(), 0, 16));
|
tempFloat = liveData->params.odoKm;
|
||||||
|
liveData->params.odoKm = liveData->decFromResponse(18, 24);
|
||||||
|
//if (tempFloat != liveData->params.odoKm) liveData->params.sdcardCanNotify = true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Aircon 7b3
|
// Aircon 7b3
|
||||||
if (this->liveData->currentAtshRequest.equals("ATSH7B3")) {
|
if (liveData->currentAtshRequest.equals("ATSH7B3")) {
|
||||||
if (this->liveData->commandRequest.equals("220100")) {
|
if (liveData->commandRequest.equals("220100")) {
|
||||||
this->liveData->params.indoorTemperature = (this->liveData->hexToDec(this->liveData->responseRowMerged.substring(16, 18).c_str(), 1, false) / 2) - 40;
|
liveData->params.indoorTemperature = (liveData->hexToDecFromResponse(16, 18, 1, false) / 2) - 40;
|
||||||
this->liveData->params.outdoorTemperature = (this->liveData->hexToDec(this->liveData->responseRowMerged.substring(18, 20).c_str(), 1, false) / 2) - 40;
|
liveData->params.outdoorTemperature = (liveData->hexToDecFromResponse(18, 20, 1, false) / 2) - 40;
|
||||||
}
|
}
|
||||||
if (this->liveData->commandRequest.equals("220102") && this->liveData->responseRowMerged.substring(12, 14) == "00") {
|
if (liveData->commandRequest.equals("220102") && liveData->responseRowMerged.substring(12, 14) == "00") {
|
||||||
this->liveData->params.coolantTemp1C = (this->liveData->hexToDec(this->liveData->responseRowMerged.substring(14, 16).c_str(), 1, false) / 2) - 40;
|
liveData->params.coolantTemp1C = (liveData->hexToDecFromResponse(14, 16, 1, false) / 2) - 40;
|
||||||
this->liveData->params.coolantTemp2C = (this->liveData->hexToDec(this->liveData->responseRowMerged.substring(16, 18).c_str(), 1, false) / 2) - 40;
|
liveData->params.coolantTemp2C = (liveData->hexToDecFromResponse(16, 18, 1, false) / 2) - 40;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// BMS 7e4
|
// BMS 7e4
|
||||||
if (this->liveData->currentAtshRequest.equals("ATSH7E4")) {
|
if (liveData->currentAtshRequest.equals("ATSH7E4")) {
|
||||||
if (this->liveData->commandRequest.equals("220101")) {
|
if (liveData->commandRequest.equals("220101")) {
|
||||||
this->liveData->params.cumulativeEnergyChargedKWh = float(strtol(this->liveData->responseRowMerged.substring(82, 90).c_str(), 0, 16)) / 10.0;
|
liveData->params.operationTimeSec = liveData->hexToDecFromResponse(98, 106, 4, false);
|
||||||
if (this->liveData->params.cumulativeEnergyChargedKWhStart == -1)
|
liveData->params.cumulativeEnergyChargedKWh = liveData->decFromResponse(82, 90) / 10.0;
|
||||||
this->liveData->params.cumulativeEnergyChargedKWhStart = this->liveData->params.cumulativeEnergyChargedKWh;
|
if (liveData->params.cumulativeEnergyChargedKWhStart == -1)
|
||||||
this->liveData->params.cumulativeEnergyDischargedKWh = float(strtol(this->liveData->responseRowMerged.substring(90, 98).c_str(), 0, 16)) / 10.0;
|
liveData->params.cumulativeEnergyChargedKWhStart = liveData->params.cumulativeEnergyChargedKWh;
|
||||||
if (this->liveData->params.cumulativeEnergyDischargedKWhStart == -1)
|
liveData->params.cumulativeEnergyDischargedKWh = liveData->decFromResponse(90, 98) / 10.0;
|
||||||
this->liveData->params.cumulativeEnergyDischargedKWhStart = this->liveData->params.cumulativeEnergyDischargedKWh;
|
if (liveData->params.cumulativeEnergyDischargedKWhStart == -1)
|
||||||
this->liveData->params.availableChargePower = float(strtol(this->liveData->responseRowMerged.substring(16, 20).c_str(), 0, 16)) / 100.0;
|
liveData->params.cumulativeEnergyDischargedKWhStart = liveData->params.cumulativeEnergyDischargedKWh;
|
||||||
this->liveData->params.availableDischargePower = float(strtol(this->liveData->responseRowMerged.substring(20, 24).c_str(), 0, 16)) / 100.0;
|
liveData->params.availableChargePower = liveData->decFromResponse(16, 20) / 100.0;
|
||||||
//this->liveData->params.isolationResistanceKOhm = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(118, 122).c_str(), 2, true);
|
liveData->params.availableDischargePower = liveData->decFromResponse(20, 24) / 100.0;
|
||||||
this->liveData->params.batFanStatus = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(60, 62).c_str(), 2, true);
|
//liveData->params.isolationResistanceKOhm = liveData->hexToDecFromResponse(118, 122, 2, true);
|
||||||
this->liveData->params.batFanFeedbackHz = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(62, 64).c_str(), 2, true);
|
liveData->params.batFanStatus = liveData->hexToDecFromResponse(60, 62, 2, true);
|
||||||
this->liveData->params.auxVoltage = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(64, 66).c_str(), 2, true) / 10.0;
|
liveData->params.batFanFeedbackHz = liveData->hexToDecFromResponse(62, 64, 2, true);
|
||||||
this->liveData->params.batPowerAmp = - this->liveData->hexToDec(this->liveData->responseRowMerged.substring(26, 30).c_str(), 2, true) / 10.0;
|
liveData->params.auxVoltage = liveData->hexToDecFromResponse(64, 66, 2, true) / 10.0;
|
||||||
this->liveData->params.batVoltage = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(30, 34).c_str(), 2, false) / 10.0;
|
liveData->params.batPowerAmp = - liveData->hexToDecFromResponse(26, 30, 2, true) / 10.0;
|
||||||
this->liveData->params.batPowerKw = (this->liveData->params.batPowerAmp * this->liveData->params.batVoltage) / 1000.0;
|
liveData->params.batVoltage = liveData->hexToDecFromResponse(30, 34, 2, false) / 10.0;
|
||||||
if (this->liveData->params.batPowerKw < 0) // Reset charging start time
|
liveData->params.batPowerKw = (liveData->params.batPowerAmp * liveData->params.batVoltage) / 1000.0;
|
||||||
this->liveData->params.chargingStartTime = this->liveData->params.currentTime;
|
if (liveData->params.batPowerKw < 0) // Reset charging start time
|
||||||
this->liveData->params.batPowerKwh100 = this->liveData->params.batPowerKw / this->liveData->params.speedKmh * 100;
|
liveData->params.chargingStartTime = liveData->params.currentTime;
|
||||||
this->liveData->params.batCellMaxV = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(52, 54).c_str(), 1, false) / 50.0;
|
liveData->params.batPowerKwh100 = liveData->params.batPowerKw / liveData->params.speedKmh * 100;
|
||||||
this->liveData->params.batCellMinV = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(56, 58).c_str(), 1, false) / 50.0;
|
liveData->params.batCellMaxV = liveData->hexToDecFromResponse(52, 54, 1, false) / 50.0;
|
||||||
this->liveData->params.batModuleTempC[0] = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(38, 40).c_str(), 1, true);
|
liveData->params.batCellMinV = liveData->hexToDecFromResponse(56, 58, 1, false) / 50.0;
|
||||||
this->liveData->params.batModuleTempC[1] = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(40, 42).c_str(), 1, true);
|
liveData->params.batModuleTempC[0] = liveData->hexToDecFromResponse(38, 40, 1, true);
|
||||||
this->liveData->params.batModuleTempC[2] = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(42, 44).c_str(), 1, true);
|
liveData->params.batModuleTempC[1] = liveData->hexToDecFromResponse(40, 42, 1, true);
|
||||||
this->liveData->params.batModuleTempC[3] = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(44, 46).c_str(), 1, true);
|
liveData->params.batModuleTempC[2] = liveData->hexToDecFromResponse(42, 44, 1, true);
|
||||||
this->liveData->params.motorRpm = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(112, 116).c_str(), 2, false);
|
liveData->params.batModuleTempC[3] = liveData->hexToDecFromResponse(44, 46, 1, true);
|
||||||
//this->liveData->params.batTempC = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(36, 38).c_str(), 1, true);
|
liveData->params.motorRpm = liveData->hexToDecFromResponse(112, 116, 2, false);
|
||||||
//this->liveData->params.batMaxC = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(34, 36).c_str(), 1, true);
|
//liveData->params.batTempC = liveData->hexToDecFromResponse(36, 38, 1, true);
|
||||||
//this->liveData->params.batMinC = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(36, 38).c_str(), 1, true);
|
//liveData->params.batMaxC = liveData->hexToDecFromResponse(34, 36, 1, true);
|
||||||
|
//liveData->params.batMinC = liveData->hexToDecFromResponse(36, 38, 1, true);
|
||||||
|
|
||||||
// This is more accurate than min/max from BMS. It's required to detect kona/eniro cold gates (min 15C is needed > 43kW charging, min 25C is needed > 58kW charging)
|
// This is more accurate than min/max from BMS. It's required to detect kona/eniro cold gates (min 15C is needed > 43kW charging, min 25C is needed > 58kW charging)
|
||||||
this->liveData->params.batMinC = this->liveData->params.batMaxC = this->liveData->params.batModuleTempC[0];
|
liveData->params.batMinC = liveData->params.batMaxC = liveData->params.batModuleTempC[0];
|
||||||
for (uint16_t i = 1; i < this->liveData->params.batModuleTempCount; i++) {
|
for (uint16_t i = 1; i < liveData->params.batModuleTempCount; i++) {
|
||||||
if (this->liveData->params.batModuleTempC[i] < this->liveData->params.batMinC)
|
if (liveData->params.batModuleTempC[i] < liveData->params.batMinC)
|
||||||
this->liveData->params.batMinC = this->liveData->params.batModuleTempC[i];
|
liveData->params.batMinC = liveData->params.batModuleTempC[i];
|
||||||
if (this->liveData->params.batModuleTempC[i] > this->liveData->params.batMaxC)
|
if (liveData->params.batModuleTempC[i] > liveData->params.batMaxC)
|
||||||
this->liveData->params.batMaxC = this->liveData->params.batModuleTempC[i];
|
liveData->params.batMaxC = liveData->params.batModuleTempC[i];
|
||||||
}
|
}
|
||||||
this->liveData->params.batTempC = this->liveData->params.batMinC;
|
liveData->params.batTempC = liveData->params.batMinC;
|
||||||
|
|
||||||
this->liveData->params.batInletC = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(50, 52).c_str(), 1, true);
|
liveData->params.batInletC = liveData->hexToDecFromResponse(50, 52, 1, true);
|
||||||
if (this->liveData->params.speedKmh < 10 && this->liveData->params.batPowerKw >= 1 && this->liveData->params.socPerc > 0 && this->liveData->params.socPerc <= 100) {
|
if (liveData->params.speedKmh < 10 && liveData->params.batPowerKw >= 1 && liveData->params.socPerc > 0 && liveData->params.socPerc <= 100) {
|
||||||
if ( this->liveData->params.chargingGraphMinKw[int(this->liveData->params.socPerc)] < 0 || this->liveData->params.batPowerKw < this->liveData->params.chargingGraphMinKw[int(this->liveData->params.socPerc)])
|
if ( liveData->params.chargingGraphMinKw[int(liveData->params.socPerc)] < 0 || liveData->params.batPowerKw < liveData->params.chargingGraphMinKw[int(liveData->params.socPerc)])
|
||||||
this->liveData->params.chargingGraphMinKw[int(this->liveData->params.socPerc)] = this->liveData->params.batPowerKw;
|
liveData->params.chargingGraphMinKw[int(liveData->params.socPerc)] = liveData->params.batPowerKw;
|
||||||
if ( this->liveData->params.chargingGraphMaxKw[int(this->liveData->params.socPerc)] < 0 || this->liveData->params.batPowerKw > this->liveData->params.chargingGraphMaxKw[int(this->liveData->params.socPerc)])
|
if ( liveData->params.chargingGraphMaxKw[int(liveData->params.socPerc)] < 0 || liveData->params.batPowerKw > liveData->params.chargingGraphMaxKw[int(liveData->params.socPerc)])
|
||||||
this->liveData->params.chargingGraphMaxKw[int(this->liveData->params.socPerc)] = this->liveData->params.batPowerKw;
|
liveData->params.chargingGraphMaxKw[int(liveData->params.socPerc)] = liveData->params.batPowerKw;
|
||||||
this->liveData->params.chargingGraphBatMinTempC[int(this->liveData->params.socPerc)] = this->liveData->params.batMinC;
|
liveData->params.chargingGraphBatMinTempC[int(liveData->params.socPerc)] = liveData->params.batMinC;
|
||||||
this->liveData->params.chargingGraphBatMaxTempC[int(this->liveData->params.socPerc)] = this->liveData->params.batMaxC;
|
liveData->params.chargingGraphBatMaxTempC[int(liveData->params.socPerc)] = liveData->params.batMaxC;
|
||||||
this->liveData->params.chargingGraphHeaterTempC[int(this->liveData->params.socPerc)] = this->liveData->params.batHeaterC;
|
liveData->params.chargingGraphHeaterTempC[int(liveData->params.socPerc)] = liveData->params.batHeaterC;
|
||||||
this->liveData->params.chargingGraphWaterCoolantTempC[int(this->liveData->params.socPerc)] = this->liveData->params.coolingWaterTempC;
|
liveData->params.chargingGraphWaterCoolantTempC[int(liveData->params.socPerc)] = liveData->params.coolingWaterTempC;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
// BMS 7e4
|
// BMS 7e4
|
||||||
if (this->liveData->commandRequest.equals("220102") && this->liveData->responseRowMerged.substring(12, 14) == "FF") {
|
if (liveData->commandRequest.equals("220102") && liveData->responseRowMerged.substring(12, 14) == "FF") {
|
||||||
for (int i = 0; i < 32; i++) {
|
for (int i = 0; i < 32; i++) {
|
||||||
this->liveData->params.cellVoltage[i] = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(14 + (i * 2), 14 + (i * 2) + 2).c_str(), 1, false) / 50;
|
liveData->params.cellVoltage[i] = liveData->hexToDecFromResponse(14 + (i * 2), 14 + (i * 2) + 2, 1, false) / 50;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
// BMS 7e4
|
// BMS 7e4
|
||||||
if (this->liveData->commandRequest.equals("220103")) {
|
if (liveData->commandRequest.equals("220103")) {
|
||||||
for (int i = 0; i < 32; i++) {
|
for (int i = 0; i < 32; i++) {
|
||||||
this->liveData->params.cellVoltage[32 + i] = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(14 + (i * 2), 14 + (i * 2) + 2).c_str(), 1, false) / 50;
|
liveData->params.cellVoltage[32 + i] = liveData->hexToDecFromResponse(14 + (i * 2), 14 + (i * 2) + 2, 1, false) / 50;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
// BMS 7e4
|
// BMS 7e4
|
||||||
if (this->liveData->commandRequest.equals("220104")) {
|
if (liveData->commandRequest.equals("220104")) {
|
||||||
for (int i = 0; i < 32; i++) {
|
for (int i = 0; i < 32; i++) {
|
||||||
this->liveData->params.cellVoltage[64 + i] = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(14 + (i * 2), 14 + (i * 2) + 2).c_str(), 1, false) / 50;
|
liveData->params.cellVoltage[64 + i] = liveData->hexToDecFromResponse(14 + (i * 2), 14 + (i * 2) + 2, 1, false) / 50;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
// BMS 7e4
|
// BMS 7e4
|
||||||
if (this->liveData->commandRequest.equals("220105")) {
|
if (liveData->commandRequest.equals("220105")) {
|
||||||
this->liveData->params.socPercPrevious = this->liveData->params.socPerc;
|
liveData->params.socPercPrevious = liveData->params.socPerc;
|
||||||
this->liveData->params.sohPerc = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(56, 60).c_str(), 2, false) / 10.0;
|
liveData->params.sohPerc = liveData->hexToDecFromResponse(56, 60, 2, false) / 10.0;
|
||||||
this->liveData->params.socPerc = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(68, 70).c_str(), 1, false) / 2.0;
|
liveData->params.socPerc = liveData->hexToDecFromResponse(68, 70, 1, false) / 2.0;
|
||||||
|
// if (liveData->params.socPercPrevious != liveData->params.socPerc) liveData->params.sdcardCanNotify = true;
|
||||||
|
|
||||||
// Soc10ced table, record x0% CEC/CED table (ex. 90%->89%, 80%->79%)
|
// Soc10ced table, record x0% CEC/CED table (ex. 90%->89%, 80%->79%)
|
||||||
if (this->liveData->params.socPercPrevious - this->liveData->params.socPerc > 0) {
|
if (liveData->params.socPercPrevious - liveData->params.socPerc > 0) {
|
||||||
byte index = (int(this->liveData->params.socPerc) == 4) ? 0 : (int)(this->liveData->params.socPerc / 10) + 1;
|
byte index = (int(liveData->params.socPerc) == 4) ? 0 : (int)(liveData->params.socPerc / 10) + 1;
|
||||||
if ((int(this->liveData->params.socPerc) % 10 == 9 || int(this->liveData->params.socPerc) == 4) && this->liveData->params.soc10ced[index] == -1) {
|
if ((int(liveData->params.socPerc) % 10 == 9 || int(liveData->params.socPerc) == 4) && liveData->params.soc10ced[index] == -1) {
|
||||||
this->liveData->params.soc10ced[index] = this->liveData->params.cumulativeEnergyDischargedKWh;
|
liveData->params.soc10ced[index] = liveData->params.cumulativeEnergyDischargedKWh;
|
||||||
this->liveData->params.soc10cec[index] = this->liveData->params.cumulativeEnergyChargedKWh;
|
liveData->params.soc10cec[index] = liveData->params.cumulativeEnergyChargedKWh;
|
||||||
this->liveData->params.soc10odo[index] = this->liveData->params.odoKm;
|
liveData->params.soc10odo[index] = liveData->params.odoKm;
|
||||||
this->liveData->params.soc10time[index] = this->liveData->params.currentTime;
|
liveData->params.soc10time[index] = liveData->params.currentTime;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
this->liveData->params.bmsUnknownTempA = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(30, 32).c_str(), 1, true);
|
liveData->params.bmsUnknownTempA = liveData->hexToDecFromResponse(30, 32, 1, true);
|
||||||
this->liveData->params.batHeaterC = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(52, 54).c_str(), 1, true);
|
liveData->params.batHeaterC = liveData->hexToDecFromResponse(52, 54, 1, true);
|
||||||
this->liveData->params.bmsUnknownTempB = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(82, 84).c_str(), 1, true);
|
liveData->params.bmsUnknownTempB = liveData->hexToDecFromResponse(82, 84, 1, true);
|
||||||
//
|
//
|
||||||
for (int i = 30; i < 32; i++) { // ai/aj position
|
for (int i = 30; i < 32; i++) { // ai/aj position
|
||||||
this->liveData->params.cellVoltage[96 - 30 + i] = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(14 + (i * 2), 14 + (i * 2) + 2).c_str(), 1, false) / 50;
|
liveData->params.cellVoltage[96 - 30 + i] = liveData->hexToDecFromResponse(14 + (i * 2), 14 + (i * 2) + 2, 1, false) / 50;
|
||||||
}
|
}
|
||||||
|
// log 220105 to sdcard
|
||||||
|
tmpStr = liveData->currentAtshRequest + '/' + liveData->commandRequest + '/' + liveData->responseRowMerged;
|
||||||
|
tmpStr.toCharArray(liveData->params.debugData, tmpStr.length() + 1);
|
||||||
}
|
}
|
||||||
// BMS 7e4
|
// BMS 7e4
|
||||||
if (this->liveData->commandRequest.equals("220106")) {
|
if (liveData->commandRequest.equals("220106")) {
|
||||||
this->liveData->params.coolingWaterTempC = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(14, 16).c_str(), 1, false);
|
liveData->params.coolingWaterTempC = liveData->hexToDecFromResponse(14, 16, 1, false);
|
||||||
this->liveData->params.bmsUnknownTempC = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(18, 20).c_str(), 1, true);
|
liveData->params.bmsUnknownTempC = liveData->hexToDecFromResponse(18, 20, 1, true);
|
||||||
this->liveData->params.bmsUnknownTempD = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(46, 48).c_str(), 1, true);
|
liveData->params.bmsUnknownTempD = liveData->hexToDecFromResponse(46, 48, 1, true);
|
||||||
|
// log 220106 to sdcard
|
||||||
|
tmpStr = liveData->currentAtshRequest + '/' + liveData->commandRequest + '/' + liveData->responseRowMerged;
|
||||||
|
tmpStr.toCharArray(liveData->params.debugData2, tmpStr.length() + 1);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// TPMS 7a0
|
// TPMS 7a0
|
||||||
if (this->liveData->currentAtshRequest.equals("ATSH7A0")) {
|
if (liveData->currentAtshRequest.equals("ATSH7A0")) {
|
||||||
if (this->liveData->commandRequest.equals("22c00b")) {
|
if (liveData->commandRequest.equals("22c00b")) {
|
||||||
this->liveData->params.tireFrontLeftPressureBar = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(14, 16).c_str(), 2, false) / 72.51886900361; // === OK Valid *0.2 / 14.503773800722
|
liveData->params.tireFrontLeftPressureBar = liveData->hexToDecFromResponse(14, 16, 2, false) / 72.51886900361; // === OK Valid *0.2 / 14.503773800722
|
||||||
this->liveData->params.tireFrontRightPressureBar = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(22, 24).c_str(), 2, false) / 72.51886900361; // === OK Valid *0.2 / 14.503773800722
|
liveData->params.tireFrontRightPressureBar = liveData->hexToDecFromResponse(22, 24, 2, false) / 72.51886900361; // === OK Valid *0.2 / 14.503773800722
|
||||||
this->liveData->params.tireRearRightPressureBar = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(30, 32).c_str(), 2, false) / 72.51886900361; // === OK Valid *0.2 / 14.503773800722
|
liveData->params.tireRearRightPressureBar = liveData->hexToDecFromResponse(30, 32, 2, false) / 72.51886900361; // === OK Valid *0.2 / 14.503773800722
|
||||||
this->liveData->params.tireRearLeftPressureBar = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(38, 40).c_str(), 2, false) / 72.51886900361; // === OK Valid *0.2 / 14.503773800722
|
liveData->params.tireRearLeftPressureBar = liveData->hexToDecFromResponse(38, 40, 2, false) / 72.51886900361; // === OK Valid *0.2 / 14.503773800722
|
||||||
this->liveData->params.tireFrontLeftTempC = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(16, 18).c_str(), 2, false) - 50; // === OK Valid
|
liveData->params.tireFrontLeftTempC = liveData->hexToDecFromResponse(16, 18, 2, false) - 50; // === OK Valid
|
||||||
this->liveData->params.tireFrontRightTempC = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(24, 26).c_str(), 2, false) - 50; // === OK Valid
|
liveData->params.tireFrontRightTempC = liveData->hexToDecFromResponse(24, 26, 2, false) - 50; // === OK Valid
|
||||||
this->liveData->params.tireRearRightTempC = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(32, 34).c_str(), 2, false) - 50; // === OK Valid
|
liveData->params.tireRearRightTempC = liveData->hexToDecFromResponse(32, 34, 2, false) - 50; // === OK Valid
|
||||||
this->liveData->params.tireRearLeftTempC = this->liveData->hexToDec(this->liveData->responseRowMerged.substring(40, 42).c_str(), 2, false) - 50; // === OK Valid
|
liveData->params.tireRearLeftTempC = liveData->hexToDecFromResponse(40, 42, 2, false) - 50; // === OK Valid
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -296,150 +308,150 @@ void CarKiaEniro::parseRowMerged() {
|
|||||||
void CarKiaEniro::loadTestData() {
|
void CarKiaEniro::loadTestData() {
|
||||||
|
|
||||||
// IGPM
|
// IGPM
|
||||||
this->liveData->currentAtshRequest = "ATSH770";
|
liveData->currentAtshRequest = "ATSH770";
|
||||||
// 22BC03
|
// 22BC03
|
||||||
this->liveData->commandRequest = "22BC03";
|
liveData->commandRequest = "22BC03";
|
||||||
this->liveData->responseRowMerged = "62BC03FDEE7C730A600000AAAA";
|
liveData->responseRowMerged = "62BC03FDEE7C730A600000AAAA";
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
|
|
||||||
// ABS / ESP + AHB ATSH7D1
|
// ABS / ESP + AHB ATSH7D1
|
||||||
this->liveData->currentAtshRequest = "ATSH7D1";
|
liveData->currentAtshRequest = "ATSH7D1";
|
||||||
// 2101
|
// 2101
|
||||||
this->liveData->commandRequest = "22C101";
|
liveData->commandRequest = "22C101";
|
||||||
this->liveData->responseRowMerged = "62C1015FD7E7D0FFFF00FF04D0D400000000FF7EFF0030F5010000FFFF7F6307F207FE05FF00FF3FFFFFAAAAAAAAAAAA";
|
liveData->responseRowMerged = "62C1015FD7E7D0FFFF00FF04D0D400000000FF7EFF0030F5010000FFFF7F6307F207FE05FF00FF3FFFFFAAAAAAAAAAAA";
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
|
|
||||||
// VMCU ATSH7E2
|
// VMCU ATSH7E2
|
||||||
this->liveData->currentAtshRequest = "ATSH7E2";
|
liveData->currentAtshRequest = "ATSH7E2";
|
||||||
// 2101
|
// 2101
|
||||||
this->liveData->commandRequest = "2101";
|
liveData->commandRequest = "2101";
|
||||||
this->liveData->responseRowMerged = "6101FFF8000009285A3B0648030000B4179D763404080805000000";
|
liveData->responseRowMerged = "6101FFF8000009285A3B0648030000B4179D763404080805000000";
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
// 2102
|
// 2102
|
||||||
this->liveData->commandRequest = "2102";
|
liveData->commandRequest = "2102";
|
||||||
this->liveData->responseRowMerged = "6102F8FFFC000101000000840FBF83BD33270680953033757F59291C76000001010100000007000000";
|
liveData->responseRowMerged = "6102F8FFFC000101000000840FBF83BD33270680953033757F59291C76000001010100000007000000";
|
||||||
this->liveData->responseRowMerged = "6102F8FFFC000101000000931CC77F4C39040BE09BA7385D8158832175000001010100000007000000";
|
liveData->responseRowMerged = "6102F8FFFC000101000000931CC77F4C39040BE09BA7385D8158832175000001010100000007000000";
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
|
|
||||||
// "ATSH7DF",
|
// "ATSH7DF",
|
||||||
this->liveData->currentAtshRequest = "ATSH7DF";
|
liveData->currentAtshRequest = "ATSH7DF";
|
||||||
// 2106
|
// 2106
|
||||||
this->liveData->commandRequest = "2106";
|
liveData->commandRequest = "2106";
|
||||||
this->liveData->responseRowMerged = "6106FFFF800000000000000200001B001C001C000600060006000E000000010000000000000000013D013D013E013E00";
|
liveData->responseRowMerged = "6106FFFF800000000000000200001B001C001C000600060006000E000000010000000000000000013D013D013E013E00";
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
|
|
||||||
// AIRCON / ACU ATSH7B3
|
// AIRCON / ACU ATSH7B3
|
||||||
this->liveData->currentAtshRequest = "ATSH7B3";
|
liveData->currentAtshRequest = "ATSH7B3";
|
||||||
// 220100
|
// 220100
|
||||||
this->liveData->commandRequest = "220100";
|
liveData->commandRequest = "220100";
|
||||||
this->liveData->responseRowMerged = "6201007E5027C8FF7F765D05B95AFFFF5AFF11FFFFFFFFFFFF6AFFFF2DF0757630FFFF00FFFF000000";
|
liveData->responseRowMerged = "6201007E5027C8FF7F765D05B95AFFFF5AFF11FFFFFFFFFFFF6AFFFF2DF0757630FFFF00FFFF000000";
|
||||||
this->liveData->responseRowMerged = "6201007E5027C8FF867C58121010FFFF10FF8EFFFFFFFFFFFF10FFFF0DF0617900FFFF01FFFF000000";
|
liveData->responseRowMerged = "6201007E5027C8FF867C58121010FFFF10FF8EFFFFFFFFFFFF10FFFF0DF0617900FFFF01FFFF000000";
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
|
|
||||||
// BMS ATSH7E4
|
// BMS ATSH7E4
|
||||||
this->liveData->currentAtshRequest = "ATSH7E4";
|
liveData->currentAtshRequest = "ATSH7E4";
|
||||||
// 220101
|
// 220101
|
||||||
this->liveData->commandRequest = "220101";
|
liveData->commandRequest = "220101";
|
||||||
this->liveData->responseRowMerged = "620101FFF7E7FF99000000000300B10EFE120F11100F12000018C438C30B00008400003864000035850000153A00001374000647010D017F0BDA0BDA03E8";
|
liveData->responseRowMerged = "620101FFF7E7FF99000000000300B10EFE120F11100F12000018C438C30B00008400003864000035850000153A00001374000647010D017F0BDA0BDA03E8";
|
||||||
this->liveData->responseRowMerged = "620101FFF7E7FFB3000000000300120F9B111011101011000014CC38CB3B00009100003A510000367C000015FB000013D3000690250D018E0000000003E8";
|
liveData->responseRowMerged = "620101FFF7E7FFB3000000000300120F9B111011101011000014CC38CB3B00009100003A510000367C000015FB000013D3000690250D018E0000000003E8";
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
// 220102
|
// 220102
|
||||||
this->liveData->commandRequest = "220102";
|
liveData->commandRequest = "220102";
|
||||||
this->liveData->responseRowMerged = "620102FFFFFFFFCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBAAAA";
|
liveData->responseRowMerged = "620102FFFFFFFFCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBAAAA";
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
// 220103
|
// 220103
|
||||||
this->liveData->commandRequest = "220103";
|
liveData->commandRequest = "220103";
|
||||||
this->liveData->responseRowMerged = "620103FFFFFFFFCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCACBCACACFCCCBCBCBCBCBCBCBCBAAAA";
|
liveData->responseRowMerged = "620103FFFFFFFFCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCACBCACACFCCCBCBCBCBCBCBCBCBAAAA";
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
// 220104
|
// 220104
|
||||||
this->liveData->commandRequest = "220104";
|
liveData->commandRequest = "220104";
|
||||||
this->liveData->responseRowMerged = "620104FFFFFFFFCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBAAAA";
|
liveData->responseRowMerged = "620104FFFFFFFFCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBAAAA";
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
// 220105
|
// 220105
|
||||||
this->liveData->commandRequest = "220105";
|
liveData->commandRequest = "220105";
|
||||||
this->liveData->responseRowMerged = "620105003fff9000000000000000000F8A86012B4946500101500DAC03E800000000AC0000C7C701000F00000000AAAA";
|
liveData->responseRowMerged = "620105003fff9000000000000000000F8A86012B4946500101500DAC03E800000000AC0000C7C701000F00000000AAAA";
|
||||||
this->liveData->responseRowMerged = "620105003FFF90000000000000000014918E012927465000015013BB03E800000000BB0000CBCB01001300000000AAAA";
|
liveData->responseRowMerged = "620105003FFF90000000000000000014918E012927465000015013BB03E800000000BB0000CBCB01001300000000AAAA";
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
// 220106
|
// 220106
|
||||||
this->liveData->commandRequest = "220106";
|
liveData->commandRequest = "220106";
|
||||||
this->liveData->responseRowMerged = "620106FFFFFFFF14001A00240000003A7C86B4B30000000928EA00";
|
liveData->responseRowMerged = "620106FFFFFFFF14001A00240000003A7C86B4B30000000928EA00";
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
|
|
||||||
// BCM / TPMS ATSH7A0
|
// BCM / TPMS ATSH7A0
|
||||||
this->liveData->currentAtshRequest = "ATSH7A0";
|
liveData->currentAtshRequest = "ATSH7A0";
|
||||||
// 22c00b
|
// 22c00b
|
||||||
this->liveData->commandRequest = "22c00b";
|
liveData->commandRequest = "22c00b";
|
||||||
this->liveData->responseRowMerged = "62C00BFFFF0000B93D0100B43E0100B43D0100BB3C0100AAAAAAAA";
|
liveData->responseRowMerged = "62C00BFFFF0000B93D0100B43E0100B43D0100BB3C0100AAAAAAAA";
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
|
|
||||||
// ATSH7C6
|
// ATSH7C6
|
||||||
this->liveData->currentAtshRequest = "ATSH7C6";
|
liveData->currentAtshRequest = "ATSH7C6";
|
||||||
// 22b002
|
// 22b002
|
||||||
this->liveData->commandRequest = "22b002";
|
liveData->commandRequest = "22b002";
|
||||||
this->liveData->responseRowMerged = "62B002E0000000FFB400330B0000000000000000";
|
liveData->responseRowMerged = "62B002E0000000FFB400330B0000000000000000";
|
||||||
this->parseRowMerged();
|
parseRowMerged();
|
||||||
|
|
||||||
this->liveData->params.batModuleTempC[0] = 28;
|
liveData->params.batModuleTempC[0] = 28;
|
||||||
this->liveData->params.batModuleTempC[1] = 29;
|
liveData->params.batModuleTempC[1] = 29;
|
||||||
this->liveData->params.batModuleTempC[2] = 28;
|
liveData->params.batModuleTempC[2] = 28;
|
||||||
this->liveData->params.batModuleTempC[3] = 30;
|
liveData->params.batModuleTempC[3] = 30;
|
||||||
|
|
||||||
// This is more accurate than min/max from BMS. It's required to detect kona/eniro cold gates (min 15C is needed > 43kW charging, min 25C is needed > 58kW charging)
|
// This is more accurate than min/max from BMS. It's required to detect kona/eniro cold gates (min 15C is needed > 43kW charging, min 25C is needed > 58kW charging)
|
||||||
this->liveData->params.batMinC = this->liveData->params.batMaxC = this->liveData->params.batModuleTempC[0];
|
liveData->params.batMinC = liveData->params.batMaxC = liveData->params.batModuleTempC[0];
|
||||||
for (uint16_t i = 1; i < this->liveData->params.batModuleTempCount; i++) {
|
for (uint16_t i = 1; i < liveData->params.batModuleTempCount; i++) {
|
||||||
if (this->liveData->params.batModuleTempC[i] < this->liveData->params.batMinC)
|
if (liveData->params.batModuleTempC[i] < liveData->params.batMinC)
|
||||||
this->liveData->params.batMinC = this->liveData->params.batModuleTempC[i];
|
liveData->params.batMinC = liveData->params.batModuleTempC[i];
|
||||||
if (this->liveData->params.batModuleTempC[i] > this->liveData->params.batMaxC)
|
if (liveData->params.batModuleTempC[i] > liveData->params.batMaxC)
|
||||||
this->liveData->params.batMaxC = this->liveData->params.batModuleTempC[i];
|
liveData->params.batMaxC = liveData->params.batModuleTempC[i];
|
||||||
}
|
}
|
||||||
this->liveData->params.batTempC = this->liveData->params.batMinC;
|
liveData->params.batTempC = liveData->params.batMinC;
|
||||||
|
|
||||||
|
|
||||||
//
|
//
|
||||||
this->liveData->params.soc10ced[10] = 2200;
|
liveData->params.soc10ced[10] = 2200;
|
||||||
this->liveData->params.soc10cec[10] = 2500;
|
liveData->params.soc10cec[10] = 2500;
|
||||||
this->liveData->params.soc10odo[10] = 13000;
|
liveData->params.soc10odo[10] = 13000;
|
||||||
this->liveData->params.soc10time[10] = 13000;
|
liveData->params.soc10time[10] = 13000;
|
||||||
this->liveData->params.soc10ced[9] = this->liveData->params.soc10ced[10] + 6.4;
|
liveData->params.soc10ced[9] = liveData->params.soc10ced[10] + 6.4;
|
||||||
this->liveData->params.soc10cec[9] = this->liveData->params.soc10cec[10] + 0;
|
liveData->params.soc10cec[9] = liveData->params.soc10cec[10] + 0;
|
||||||
this->liveData->params.soc10odo[9] = this->liveData->params.soc10odo[10] + 30;
|
liveData->params.soc10odo[9] = liveData->params.soc10odo[10] + 30;
|
||||||
this->liveData->params.soc10time[9] = this->liveData->params.soc10time[10] + 900;
|
liveData->params.soc10time[9] = liveData->params.soc10time[10] + 900;
|
||||||
this->liveData->params.soc10ced[8] = this->liveData->params.soc10ced[9] + 6.8;
|
liveData->params.soc10ced[8] = liveData->params.soc10ced[9] + 6.8;
|
||||||
this->liveData->params.soc10cec[8] = this->liveData->params.soc10cec[9] + 0;
|
liveData->params.soc10cec[8] = liveData->params.soc10cec[9] + 0;
|
||||||
this->liveData->params.soc10odo[8] = this->liveData->params.soc10odo[9] + 30;
|
liveData->params.soc10odo[8] = liveData->params.soc10odo[9] + 30;
|
||||||
this->liveData->params.soc10time[8] = this->liveData->params.soc10time[9] + 900;
|
liveData->params.soc10time[8] = liveData->params.soc10time[9] + 900;
|
||||||
this->liveData->params.soc10ced[7] = this->liveData->params.soc10ced[8] + 7.2;
|
liveData->params.soc10ced[7] = liveData->params.soc10ced[8] + 7.2;
|
||||||
this->liveData->params.soc10cec[7] = this->liveData->params.soc10cec[8] + 0.6;
|
liveData->params.soc10cec[7] = liveData->params.soc10cec[8] + 0.6;
|
||||||
this->liveData->params.soc10odo[7] = this->liveData->params.soc10odo[8] + 30;
|
liveData->params.soc10odo[7] = liveData->params.soc10odo[8] + 30;
|
||||||
this->liveData->params.soc10time[7] = this->liveData->params.soc10time[8] + 900;
|
liveData->params.soc10time[7] = liveData->params.soc10time[8] + 900;
|
||||||
this->liveData->params.soc10ced[6] = this->liveData->params.soc10ced[7] + 6.7;
|
liveData->params.soc10ced[6] = liveData->params.soc10ced[7] + 6.7;
|
||||||
this->liveData->params.soc10cec[6] = this->liveData->params.soc10cec[7] + 0;
|
liveData->params.soc10cec[6] = liveData->params.soc10cec[7] + 0;
|
||||||
this->liveData->params.soc10odo[6] = this->liveData->params.soc10odo[7] + 30;
|
liveData->params.soc10odo[6] = liveData->params.soc10odo[7] + 30;
|
||||||
this->liveData->params.soc10time[6] = this->liveData->params.soc10time[7] + 900;
|
liveData->params.soc10time[6] = liveData->params.soc10time[7] + 900;
|
||||||
this->liveData->params.soc10ced[5] = this->liveData->params.soc10ced[6] + 6.7;
|
liveData->params.soc10ced[5] = liveData->params.soc10ced[6] + 6.7;
|
||||||
this->liveData->params.soc10cec[5] = this->liveData->params.soc10cec[6] + 0;
|
liveData->params.soc10cec[5] = liveData->params.soc10cec[6] + 0;
|
||||||
this->liveData->params.soc10odo[5] = this->liveData->params.soc10odo[6] + 30;
|
liveData->params.soc10odo[5] = liveData->params.soc10odo[6] + 30;
|
||||||
this->liveData->params.soc10time[5] = this->liveData->params.soc10time[6] + 900;
|
liveData->params.soc10time[5] = liveData->params.soc10time[6] + 900;
|
||||||
this->liveData->params.soc10ced[4] = this->liveData->params.soc10ced[5] + 6.4;
|
liveData->params.soc10ced[4] = liveData->params.soc10ced[5] + 6.4;
|
||||||
this->liveData->params.soc10cec[4] = this->liveData->params.soc10cec[5] + 0.3;
|
liveData->params.soc10cec[4] = liveData->params.soc10cec[5] + 0.3;
|
||||||
this->liveData->params.soc10odo[4] = this->liveData->params.soc10odo[5] + 30;
|
liveData->params.soc10odo[4] = liveData->params.soc10odo[5] + 30;
|
||||||
this->liveData->params.soc10time[4] = this->liveData->params.soc10time[5] + 900;
|
liveData->params.soc10time[4] = liveData->params.soc10time[5] + 900;
|
||||||
this->liveData->params.soc10ced[3] = this->liveData->params.soc10ced[4] + 6.4;
|
liveData->params.soc10ced[3] = liveData->params.soc10ced[4] + 6.4;
|
||||||
this->liveData->params.soc10cec[3] = this->liveData->params.soc10cec[4] + 0;
|
liveData->params.soc10cec[3] = liveData->params.soc10cec[4] + 0;
|
||||||
this->liveData->params.soc10odo[3] = this->liveData->params.soc10odo[4] + 30;
|
liveData->params.soc10odo[3] = liveData->params.soc10odo[4] + 30;
|
||||||
this->liveData->params.soc10time[3] = this->liveData->params.soc10time[4] + 900;
|
liveData->params.soc10time[3] = liveData->params.soc10time[4] + 900;
|
||||||
this->liveData->params.soc10ced[2] = this->liveData->params.soc10ced[3] + 5.4;
|
liveData->params.soc10ced[2] = liveData->params.soc10ced[3] + 5.4;
|
||||||
this->liveData->params.soc10cec[2] = this->liveData->params.soc10cec[3] + 0.1;
|
liveData->params.soc10cec[2] = liveData->params.soc10cec[3] + 0.1;
|
||||||
this->liveData->params.soc10odo[2] = this->liveData->params.soc10odo[3] + 30;
|
liveData->params.soc10odo[2] = liveData->params.soc10odo[3] + 30;
|
||||||
this->liveData->params.soc10time[2] = this->liveData->params.soc10time[3] + 900;
|
liveData->params.soc10time[2] = liveData->params.soc10time[3] + 900;
|
||||||
this->liveData->params.soc10ced[1] = this->liveData->params.soc10ced[2] + 6.2;
|
liveData->params.soc10ced[1] = liveData->params.soc10ced[2] + 6.2;
|
||||||
this->liveData->params.soc10cec[1] = this->liveData->params.soc10cec[2] + 0.1;
|
liveData->params.soc10cec[1] = liveData->params.soc10cec[2] + 0.1;
|
||||||
this->liveData->params.soc10odo[1] = this->liveData->params.soc10odo[2] + 30;
|
liveData->params.soc10odo[1] = liveData->params.soc10odo[2] + 30;
|
||||||
this->liveData->params.soc10time[1] = this->liveData->params.soc10time[2] + 900;
|
liveData->params.soc10time[1] = liveData->params.soc10time[2] + 900;
|
||||||
this->liveData->params.soc10ced[0] = this->liveData->params.soc10ced[1] + 2.9;
|
liveData->params.soc10ced[0] = liveData->params.soc10ced[1] + 2.9;
|
||||||
this->liveData->params.soc10cec[0] = this->liveData->params.soc10cec[1] + 0.5;
|
liveData->params.soc10cec[0] = liveData->params.soc10cec[1] + 0.5;
|
||||||
this->liveData->params.soc10odo[0] = this->liveData->params.soc10odo[1] + 15;
|
liveData->params.soc10odo[0] = liveData->params.soc10odo[1] + 15;
|
||||||
this->liveData->params.soc10time[0] = this->liveData->params.soc10time[1] + 900;
|
liveData->params.soc10time[0] = liveData->params.soc10time[1] + 900;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -5,7 +5,7 @@
|
|||||||
|
|
||||||
class CarKiaEniro : public CarInterface {
|
class CarKiaEniro : public CarInterface {
|
||||||
|
|
||||||
private:
|
protected:
|
||||||
|
|
||||||
public:
|
public:
|
||||||
void activateCommandQueue() override;
|
void activateCommandQueue() override;
|
||||||
|
|||||||
380
CarKiaNiroPhev.cpp
Normal file
380
CarKiaNiroPhev.cpp
Normal file
@@ -0,0 +1,380 @@
|
|||||||
|
#ifndef CARKIANIROPHEV_CPP
|
||||||
|
#define CARKIANIROPHEV_CPP
|
||||||
|
|
||||||
|
#include "CarKiaNiroPhev.h"
|
||||||
|
|
||||||
|
#define commandQueueCountKiaNiroPhev 25
|
||||||
|
#define commandQueueLoopFromKiaNiroPhev 8
|
||||||
|
|
||||||
|
/**
|
||||||
|
activateliveData->commandQueue
|
||||||
|
*/
|
||||||
|
void CarKiaNiroPhev::activateCommandQueue() {
|
||||||
|
|
||||||
|
String commandQueueKiaNiroPhev[commandQueueCountKiaNiroPhev] = {
|
||||||
|
"AT Z", // Reset all
|
||||||
|
"AT I", // Print the version ID
|
||||||
|
"AT E0", // Echo off
|
||||||
|
"AT L0", // Linefeeds off
|
||||||
|
"AT S0", // Printing of spaces on
|
||||||
|
"AT SP 6", // Select protocol to ISO 15765-4 CAN (11 bit ID, 500 kbit/s)
|
||||||
|
//"AT AL", // Allow Long (>7 byte) messages
|
||||||
|
//"AT AR", // Automatically receive
|
||||||
|
//"AT H1", // Headers on (debug only)
|
||||||
|
//"AT D1", // Display of the DLC on
|
||||||
|
//"AT CAF0", // Automatic formatting off
|
||||||
|
"AT DP",
|
||||||
|
"AT ST16",
|
||||||
|
|
||||||
|
// Loop from (HYUNDAI IONIQ)
|
||||||
|
// BMS
|
||||||
|
"ATSH7E4",
|
||||||
|
"2101", // power kw, ...
|
||||||
|
"2102", // cell voltages, screen 3 only
|
||||||
|
"2103", // cell voltages, screen 3 only
|
||||||
|
"2104", // cell voltages, screen 3 only
|
||||||
|
"2105", // soh, soc, ..
|
||||||
|
"2106", // cooling water temp
|
||||||
|
|
||||||
|
// VMCU
|
||||||
|
"ATSH7E2",
|
||||||
|
"2101", // speed, ...
|
||||||
|
"2102", // aux, ...
|
||||||
|
|
||||||
|
//"ATSH7Df",
|
||||||
|
//"2106",
|
||||||
|
//"220106",
|
||||||
|
|
||||||
|
// Aircondition
|
||||||
|
// IONIQ OK
|
||||||
|
"ATSH7B3",
|
||||||
|
"220100", // in/out temp
|
||||||
|
"220102", // coolant temp1, 2
|
||||||
|
|
||||||
|
// BCM / TPMS
|
||||||
|
// IONIQ OK
|
||||||
|
"ATSH7A0",
|
||||||
|
"22c00b", // tire pressure/temp
|
||||||
|
|
||||||
|
// CLUSTER MODULE
|
||||||
|
// IONIQ OK
|
||||||
|
"ATSH7C6",
|
||||||
|
"22B002", // odo
|
||||||
|
};
|
||||||
|
|
||||||
|
// 28kWh version
|
||||||
|
liveData->params.batteryTotalAvailableKWh = 8.9;
|
||||||
|
liveData->params.batModuleTempCount = 5;
|
||||||
|
|
||||||
|
// Empty and fill command queue
|
||||||
|
for (int i = 0; i < 300; i++) {
|
||||||
|
liveData->commandQueue[i] = "";
|
||||||
|
}
|
||||||
|
for (int i = 0; i < commandQueueCountKiaNiroPhev; i++) {
|
||||||
|
liveData->commandQueue[i] = commandQueueKiaNiroPhev[i];
|
||||||
|
}
|
||||||
|
|
||||||
|
liveData->commandQueueLoopFrom = commandQueueLoopFromKiaNiroPhev;
|
||||||
|
liveData->commandQueueCount = commandQueueCountKiaNiroPhev;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
parseRowMerged
|
||||||
|
*/
|
||||||
|
void CarKiaNiroPhev::parseRowMerged() {
|
||||||
|
|
||||||
|
// VMCU 7E2
|
||||||
|
if (liveData->currentAtshRequest.equals("ATSH7E2")) {
|
||||||
|
if (liveData->commandRequest.equals("2101")) {
|
||||||
|
liveData->params.speedKmh = liveData->hexToDecFromResponse(32, 36, 2, false) * 0.0155; // / 100.0 *1.609 = real to gps is 1.750
|
||||||
|
if (liveData->params.speedKmh < -99 || liveData->params.speedKmh > 200)
|
||||||
|
liveData->params.speedKmh = 0;
|
||||||
|
}
|
||||||
|
if (liveData->commandRequest.equals("2102")) {
|
||||||
|
liveData->params.auxPerc = liveData->hexToDecFromResponse(50, 52, 1, false);
|
||||||
|
liveData->params.auxCurrentAmp = - liveData->hexToDecFromResponse(46, 50, 2, true) / 1000.0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Cluster module 7c6
|
||||||
|
if (liveData->currentAtshRequest.equals("ATSH7C6")) {
|
||||||
|
if (liveData->commandRequest.equals("22B002")) {
|
||||||
|
liveData->params.odoKm = liveData->decFromResponse(18, 24);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Aircon 7b3
|
||||||
|
if (liveData->currentAtshRequest.equals("ATSH7B3")) {
|
||||||
|
if (liveData->commandRequest.equals("220100")) {
|
||||||
|
liveData->params.indoorTemperature = (liveData->hexToDecFromResponse(16, 18, 1, false) / 2) - 40;
|
||||||
|
liveData->params.outdoorTemperature = (liveData->hexToDecFromResponse(18, 20, 1, false) / 2) - 40;
|
||||||
|
}
|
||||||
|
if (liveData->commandRequest.equals("220102") && liveData->responseRowMerged.substring(12, 14) == "00") {
|
||||||
|
liveData->params.coolantTemp1C = (liveData->hexToDecFromResponse(14, 16, 1, false) / 2) - 40;
|
||||||
|
liveData->params.coolantTemp2C = (liveData->hexToDecFromResponse(16, 18, 1, false) / 2) - 40;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// BMS 7e4
|
||||||
|
if (liveData->currentAtshRequest.equals("ATSH7E4")) {
|
||||||
|
if (liveData->commandRequest.equals("2101")) {
|
||||||
|
liveData->params.cumulativeEnergyChargedKWh = liveData->decFromResponse(80, 88) / 10.0;
|
||||||
|
if (liveData->params.cumulativeEnergyChargedKWhStart == -1)
|
||||||
|
liveData->params.cumulativeEnergyChargedKWhStart = liveData->params.cumulativeEnergyChargedKWh;
|
||||||
|
liveData->params.cumulativeEnergyDischargedKWh = liveData->decFromResponse(88, 96) / 10.0;
|
||||||
|
if (liveData->params.cumulativeEnergyDischargedKWhStart == -1)
|
||||||
|
liveData->params.cumulativeEnergyDischargedKWhStart = liveData->params.cumulativeEnergyDischargedKWh;
|
||||||
|
liveData->params.availableChargePower = liveData->decFromResponse(16, 20) / 100.0;
|
||||||
|
liveData->params.availableDischargePower = liveData->decFromResponse(20, 24) / 100.0;
|
||||||
|
liveData->params.isolationResistanceKOhm = liveData->hexToDecFromResponse(118, 122, 2, true);
|
||||||
|
liveData->params.batFanStatus = liveData->hexToDecFromResponse(58, 60, 2, true);
|
||||||
|
liveData->params.batFanFeedbackHz = liveData->hexToDecFromResponse(60, 62, 2, true);
|
||||||
|
liveData->params.auxVoltage = liveData->hexToDecFromResponse(62, 64, 2, true) / 10.0;
|
||||||
|
liveData->params.batPowerAmp = - liveData->hexToDecFromResponse(24, 28, 2, true) / 10.0;
|
||||||
|
liveData->params.batVoltage = liveData->hexToDecFromResponse(28, 32, 2, false) / 10.0;
|
||||||
|
liveData->params.batPowerKw = (liveData->params.batPowerAmp * liveData->params.batVoltage) / 1000.0;
|
||||||
|
if (liveData->params.batPowerKw < 1) // Reset charging start time
|
||||||
|
liveData->params.chargingStartTime = liveData->params.currentTime;
|
||||||
|
liveData->params.batPowerKwh100 = liveData->params.batPowerKw / liveData->params.speedKmh * 100;
|
||||||
|
liveData->params.batCellMaxV = liveData->hexToDecFromResponse(50, 52, 1, false) / 50.0;
|
||||||
|
liveData->params.batCellMinV = liveData->hexToDecFromResponse(54, 56, 1, false) / 50.0;
|
||||||
|
liveData->params.batModuleTempC[0] = liveData->hexToDecFromResponse(36, 38, 1, true);
|
||||||
|
liveData->params.batModuleTempC[1] = liveData->hexToDecFromResponse(38, 40, 1, true);
|
||||||
|
liveData->params.batModuleTempC[2] = liveData->hexToDecFromResponse(40, 42, 1, true);
|
||||||
|
liveData->params.batModuleTempC[3] = liveData->hexToDecFromResponse(42, 44, 1, true);
|
||||||
|
liveData->params.batModuleTempC[4] = liveData->hexToDecFromResponse(44, 46, 1, true);
|
||||||
|
//liveData->params.batTempC = liveData->hexToDecFromResponse(34, 36, 1, true);
|
||||||
|
//liveData->params.batMaxC = liveData->hexToDecFromResponse(32, 34, 1, true);
|
||||||
|
//liveData->params.batMinC = liveData->hexToDecFromResponse(34, 36, 1, true);
|
||||||
|
|
||||||
|
// This is more accurate than min/max from BMS. It's required to detect kona/eniro cold gates (min 15C is needed > 43kW charging, min 25C is needed > 58kW charging)
|
||||||
|
liveData->params.batInletC = liveData->hexToDecFromResponse(48, 50, 1, true);
|
||||||
|
if (liveData->params.speedKmh < 10 && liveData->params.batPowerKw >= 1 && liveData->params.socPerc > 0 && liveData->params.socPerc <= 100) {
|
||||||
|
if ( liveData->params.chargingGraphMinKw[int(liveData->params.socPerc)] == -100 || liveData->params.batPowerKw < liveData->params.chargingGraphMinKw[int(liveData->params.socPerc)])
|
||||||
|
liveData->params.chargingGraphMinKw[int(liveData->params.socPerc)] = liveData->params.batPowerKw;
|
||||||
|
if ( liveData->params.chargingGraphMaxKw[int(liveData->params.socPerc)] == -100 || liveData->params.batPowerKw > liveData->params.chargingGraphMaxKw[int(liveData->params.socPerc)])
|
||||||
|
liveData->params.chargingGraphMaxKw[int(liveData->params.socPerc)] = liveData->params.batPowerKw;
|
||||||
|
liveData->params.chargingGraphBatMinTempC[int(liveData->params.socPerc)] = liveData->params.batMinC;
|
||||||
|
liveData->params.chargingGraphBatMaxTempC[int(liveData->params.socPerc)] = liveData->params.batMaxC;
|
||||||
|
liveData->params.chargingGraphHeaterTempC[int(liveData->params.socPerc)] = liveData->params.batHeaterC;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
// BMS 7e4
|
||||||
|
if (liveData->commandRequest.equals("2102") && liveData->responseRowMerged.substring(10, 12) == "FF") {
|
||||||
|
for (int i = 0; i < 32; i++) {
|
||||||
|
liveData->params.cellVoltage[i] = liveData->hexToDecFromResponse(12 + (i * 2), 12 + (i * 2) + 2, 1, false) / 50;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
// BMS 7e4
|
||||||
|
if (liveData->commandRequest.equals("2103")) {
|
||||||
|
for (int i = 0; i < 32; i++) {
|
||||||
|
liveData->params.cellVoltage[32 + i] = liveData->hexToDecFromResponse(12 + (i * 2), 12 + (i * 2) + 2, 1, false) / 50;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
// BMS 7e4
|
||||||
|
if (liveData->commandRequest.equals("2104")) {
|
||||||
|
for (int i = 0; i < 32; i++) {
|
||||||
|
liveData->params.cellVoltage[64 + i] = liveData->hexToDecFromResponse(12 + (i * 2), 12 + (i * 2) + 2, 1, false) / 50;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
// BMS 7e4
|
||||||
|
if (liveData->commandRequest.equals("2105")) {
|
||||||
|
liveData->params.socPercPrevious = liveData->params.socPerc;
|
||||||
|
liveData->params.sohPerc = liveData->hexToDecFromResponse(54, 58, 2, false) / 10.0;
|
||||||
|
liveData->params.socPerc = liveData->hexToDecFromResponse(66, 68, 1, false) / 2.0;
|
||||||
|
|
||||||
|
// Remaining battery modules (tempC)
|
||||||
|
liveData->params.batModuleTempC[5] = liveData->hexToDecFromResponse(22, 24, 1, true);
|
||||||
|
liveData->params.batModuleTempC[6] = liveData->hexToDecFromResponse(24, 26, 1, true);
|
||||||
|
liveData->params.batModuleTempC[7] = liveData->hexToDecFromResponse(26, 28, 1, true);
|
||||||
|
liveData->params.batModuleTempC[8] = liveData->hexToDecFromResponse(28, 30, 1, true);
|
||||||
|
liveData->params.batModuleTempC[9] = liveData->hexToDecFromResponse(30, 32, 1, true);
|
||||||
|
liveData->params.batModuleTempC[10] = liveData->hexToDecFromResponse(32, 34, 1, true);
|
||||||
|
liveData->params.batModuleTempC[11] = liveData->hexToDecFromResponse(34, 36, 1, true);
|
||||||
|
|
||||||
|
liveData->params.batMinC = liveData->params.batMaxC = liveData->params.batModuleTempC[0];
|
||||||
|
for (uint16_t i = 1; i < liveData->params.batModuleTempCount; i++) {
|
||||||
|
if (liveData->params.batModuleTempC[i] < liveData->params.batMinC)
|
||||||
|
liveData->params.batMinC = liveData->params.batModuleTempC[i];
|
||||||
|
if (liveData->params.batModuleTempC[i] > liveData->params.batMaxC)
|
||||||
|
liveData->params.batMaxC = liveData->params.batModuleTempC[i];
|
||||||
|
}
|
||||||
|
liveData->params.batTempC = liveData->params.batMinC;
|
||||||
|
|
||||||
|
// Soc10ced table, record x0% CEC/CED table (ex. 90%->89%, 80%->79%)
|
||||||
|
if (liveData->params.socPercPrevious - liveData->params.socPerc > 0) {
|
||||||
|
byte index = (int(liveData->params.socPerc) == 4) ? 0 : (int)(liveData->params.socPerc / 10) + 1;
|
||||||
|
if ((int(liveData->params.socPerc) % 10 == 9 || int(liveData->params.socPerc) == 4) && liveData->params.soc10ced[index] == -1) {
|
||||||
|
liveData->params.soc10ced[index] = liveData->params.cumulativeEnergyDischargedKWh;
|
||||||
|
liveData->params.soc10cec[index] = liveData->params.cumulativeEnergyChargedKWh;
|
||||||
|
liveData->params.soc10odo[index] = liveData->params.odoKm;
|
||||||
|
liveData->params.soc10time[index] = liveData->params.currentTime;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
liveData->params.batHeaterC = liveData->hexToDecFromResponse(50, 52, 1, true);
|
||||||
|
//
|
||||||
|
for (int i = 30; i < 32; i++) { // ai/aj position
|
||||||
|
liveData->params.cellVoltage[96 - 30 + i] = -1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
// BMS 7e4
|
||||||
|
if (liveData->commandRequest.equals("2106")) {
|
||||||
|
liveData->params.coolingWaterTempC = liveData->hexToDecFromResponse(14, 16, 1, false);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// TPMS 7a0
|
||||||
|
if (liveData->currentAtshRequest.equals("ATSH7A0")) {
|
||||||
|
if (liveData->commandRequest.equals("22c00b")) {
|
||||||
|
liveData->params.tireFrontLeftPressureBar = liveData->hexToDecFromResponse(14, 16, 2, false) / 72.51886900361; // === OK Valid *0.2 / 14.503773800722
|
||||||
|
liveData->params.tireFrontRightPressureBar = liveData->hexToDecFromResponse(22, 24, 2, false) / 72.51886900361; // === OK Valid *0.2 / 14.503773800722
|
||||||
|
liveData->params.tireRearRightPressureBar = liveData->hexToDecFromResponse(30, 32, 2, false) / 72.51886900361; // === OK Valid *0.2 / 14.503773800722
|
||||||
|
liveData->params.tireRearLeftPressureBar = liveData->hexToDecFromResponse(38, 40, 2, false) / 72.51886900361; // === OK Valid *0.2 / 14.503773800722
|
||||||
|
liveData->params.tireFrontLeftTempC = liveData->hexToDecFromResponse(16, 18, 2, false) - 50; // === OK Valid
|
||||||
|
liveData->params.tireFrontRightTempC = liveData->hexToDecFromResponse(24, 26, 2, false) - 50; // === OK Valid
|
||||||
|
liveData->params.tireRearRightTempC = liveData->hexToDecFromResponse(32, 34, 2, false) - 50; // === OK Valid
|
||||||
|
liveData->params.tireRearLeftTempC = liveData->hexToDecFromResponse(40, 42, 2, false) - 50; // === OK Valid
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
loadTestData
|
||||||
|
*/
|
||||||
|
void CarKiaNiroPhev::loadTestData() {
|
||||||
|
|
||||||
|
// VMCU ATSH7E2
|
||||||
|
liveData->currentAtshRequest = "ATSH7E2";
|
||||||
|
// 2101
|
||||||
|
liveData->commandRequest = "2101";
|
||||||
|
liveData->responseRowMerged = "6101FFE0000009211222062F03000000001D7734";
|
||||||
|
parseRowMerged();
|
||||||
|
// 2102
|
||||||
|
liveData->commandRequest = "2102";
|
||||||
|
liveData->responseRowMerged = "6102FF80000001010000009315B2888D390B08618B683900000000";
|
||||||
|
parseRowMerged();
|
||||||
|
|
||||||
|
// "ATSH7DF",
|
||||||
|
liveData->currentAtshRequest = "ATSH7DF";
|
||||||
|
|
||||||
|
// AIRCON / ACU ATSH7B3
|
||||||
|
liveData->currentAtshRequest = "ATSH7B3";
|
||||||
|
// 220100
|
||||||
|
liveData->commandRequest = "220100";
|
||||||
|
liveData->responseRowMerged = "6201007E5007C8FF8A876A011010FFFF10FF10FFFFFFFFFFFFFFFFFF2EEF767D00FFFF00FFFF000000";
|
||||||
|
parseRowMerged();
|
||||||
|
// 220102
|
||||||
|
liveData->commandRequest = "220102";
|
||||||
|
liveData->responseRowMerged = "620102FF800000A3950000000000002600000000";
|
||||||
|
parseRowMerged();
|
||||||
|
|
||||||
|
// BMS ATSH7E4
|
||||||
|
liveData->currentAtshRequest = "ATSH7E4";
|
||||||
|
// 220101
|
||||||
|
liveData->commandRequest = "2101";
|
||||||
|
liveData->responseRowMerged = "6101FFFFFFFF5026482648A3FFC30D9E181717171718170019B50FB501000090000142230001425F0000771B00007486007815D809015C0000000003E800";
|
||||||
|
parseRowMerged();
|
||||||
|
// 220102
|
||||||
|
liveData->commandRequest = "2102";
|
||||||
|
liveData->responseRowMerged = "6102FFFFFFFFB5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5000000";
|
||||||
|
parseRowMerged();
|
||||||
|
// 220103
|
||||||
|
liveData->commandRequest = "2103";
|
||||||
|
liveData->responseRowMerged = "6103FFFFFFFFB5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5000000";
|
||||||
|
parseRowMerged();
|
||||||
|
// 220104
|
||||||
|
liveData->commandRequest = "2104";
|
||||||
|
liveData->responseRowMerged = "6104FFFFFFFFB5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5B5000000";
|
||||||
|
parseRowMerged();
|
||||||
|
// 220105
|
||||||
|
liveData->commandRequest = "2105";
|
||||||
|
liveData->responseRowMerged = "6105FFFFFFFF00000000001717171817171726482648000150181703E81A03E801520029000000000000000000000000";
|
||||||
|
parseRowMerged();
|
||||||
|
// 220106
|
||||||
|
liveData->commandRequest = "2106";
|
||||||
|
liveData->responseRowMerged = "7F2112"; // n/a on ioniq
|
||||||
|
parseRowMerged();
|
||||||
|
|
||||||
|
// BCM / TPMS ATSH7A0
|
||||||
|
liveData->currentAtshRequest = "ATSH7A0";
|
||||||
|
// 22c00b
|
||||||
|
liveData->commandRequest = "22c00b";
|
||||||
|
liveData->responseRowMerged = "62C00BFFFF0000B9510100B9510100B84F0100B54F0100AAAAAAAA";
|
||||||
|
parseRowMerged();
|
||||||
|
|
||||||
|
// ATSH7C6
|
||||||
|
liveData->currentAtshRequest = "ATSH7C6";
|
||||||
|
// 22b002
|
||||||
|
liveData->commandRequest = "22b002";
|
||||||
|
liveData->responseRowMerged = "62B002E000000000AD003D2D0000000000000000";
|
||||||
|
parseRowMerged();
|
||||||
|
|
||||||
|
/* liveData->params.batModule01TempC = 28;
|
||||||
|
liveData->params.batModule02TempC = 29;
|
||||||
|
liveData->params.batModule03TempC = 28;
|
||||||
|
liveData->params.batModule04TempC = 30;
|
||||||
|
//liveData->params.batTempC = liveData->hexToDecFromResponse(36, 38, 1, true);
|
||||||
|
//liveData->params.batMaxC = liveData->hexToDecFromResponse(34, 36, 1, true);
|
||||||
|
//liveData->params.batMinC = liveData->hexToDecFromResponse(36, 38, 1, true);
|
||||||
|
|
||||||
|
// This is more accurate than min/max from BMS. It's required to detect kona/eniro cold gates (min 15C is needed > 43kW charging, min 25C is needed > 58kW charging)
|
||||||
|
liveData->params.batMinC = liveData->params.batMaxC = liveData->params.batModule01TempC;
|
||||||
|
liveData->params.batMinC = (liveData->params.batModule02TempC < liveData->params.batMinC) ? liveData->params.batModule02TempC : liveData->params.batMinC ;
|
||||||
|
liveData->params.batMinC = (liveData->params.batModule03TempC < liveData->params.batMinC) ? liveData->params.batModule03TempC : liveData->params.batMinC ;
|
||||||
|
liveData->params.batMinC = (liveData->params.batModule04TempC < liveData->params.batMinC) ? liveData->params.batModule04TempC : liveData->params.batMinC ;
|
||||||
|
liveData->params.batMaxC = (liveData->params.batModule02TempC > liveData->params.batMaxC) ? liveData->params.batModule02TempC : liveData->params.batMaxC ;
|
||||||
|
liveData->params.batMaxC = (liveData->params.batModule03TempC > liveData->params.batMaxC) ? liveData->params.batModule03TempC : liveData->params.batMaxC ;
|
||||||
|
liveData->params.batMaxC = (liveData->params.batModule04TempC > liveData->params.batMaxC) ? liveData->params.batModule04TempC : liveData->params.batMaxC ;
|
||||||
|
liveData->params.batTempC = liveData->params.batMinC;
|
||||||
|
|
||||||
|
//
|
||||||
|
liveData->params.soc10ced[10] = 2200;
|
||||||
|
liveData->params.soc10cec[10] = 2500;
|
||||||
|
liveData->params.soc10odo[10] = 13000;
|
||||||
|
liveData->params.soc10time[10] = 13000;
|
||||||
|
liveData->params.soc10ced[9] = liveData->params.soc10ced[10] + 6.4;
|
||||||
|
liveData->params.soc10cec[9] = liveData->params.soc10cec[10] + 0;
|
||||||
|
liveData->params.soc10odo[9] = liveData->params.soc10odo[10] + 30;
|
||||||
|
liveData->params.soc10time[9] = liveData->params.soc10time[10] + 900;
|
||||||
|
liveData->params.soc10ced[8] = liveData->params.soc10ced[9] + 6.8;
|
||||||
|
liveData->params.soc10cec[8] = liveData->params.soc10cec[9] + 0;
|
||||||
|
liveData->params.soc10odo[8] = liveData->params.soc10odo[9] + 30;
|
||||||
|
liveData->params.soc10time[8] = liveData->params.soc10time[9] + 900;
|
||||||
|
liveData->params.soc10ced[7] = liveData->params.soc10ced[8] + 7.2;
|
||||||
|
liveData->params.soc10cec[7] = liveData->params.soc10cec[8] + 0.6;
|
||||||
|
liveData->params.soc10odo[7] = liveData->params.soc10odo[8] + 30;
|
||||||
|
liveData->params.soc10time[7] = liveData->params.soc10time[8] + 900;
|
||||||
|
liveData->params.soc10ced[6] = liveData->params.soc10ced[7] + 6.7;
|
||||||
|
liveData->params.soc10cec[6] = liveData->params.soc10cec[7] + 0;
|
||||||
|
liveData->params.soc10odo[6] = liveData->params.soc10odo[7] + 30;
|
||||||
|
liveData->params.soc10time[6] = liveData->params.soc10time[7] + 900;
|
||||||
|
liveData->params.soc10ced[5] = liveData->params.soc10ced[6] + 6.7;
|
||||||
|
liveData->params.soc10cec[5] = liveData->params.soc10cec[6] + 0;
|
||||||
|
liveData->params.soc10odo[5] = liveData->params.soc10odo[6] + 30;
|
||||||
|
liveData->params.soc10time[5] = liveData->params.soc10time[6] + 900;
|
||||||
|
liveData->params.soc10ced[4] = liveData->params.soc10ced[5] + 6.4;
|
||||||
|
liveData->params.soc10cec[4] = liveData->params.soc10cec[5] + 0.3;
|
||||||
|
liveData->params.soc10odo[4] = liveData->params.soc10odo[5] + 30;
|
||||||
|
liveData->params.soc10time[4] = liveData->params.soc10time[5] + 900;
|
||||||
|
liveData->params.soc10ced[3] = liveData->params.soc10ced[4] + 6.4;
|
||||||
|
liveData->params.soc10cec[3] = liveData->params.soc10cec[4] + 0;
|
||||||
|
liveData->params.soc10odo[3] = liveData->params.soc10odo[4] + 30;
|
||||||
|
liveData->params.soc10time[3] = liveData->params.soc10time[4] + 900;
|
||||||
|
liveData->params.soc10ced[2] = liveData->params.soc10ced[3] + 5.4;
|
||||||
|
liveData->params.soc10cec[2] = liveData->params.soc10cec[3] + 0.1;
|
||||||
|
liveData->params.soc10odo[2] = liveData->params.soc10odo[3] + 30;
|
||||||
|
liveData->params.soc10time[2] = liveData->params.soc10time[3] + 900;
|
||||||
|
liveData->params.soc10ced[1] = liveData->params.soc10ced[2] + 6.2;
|
||||||
|
liveData->params.soc10cec[1] = liveData->params.soc10cec[2] + 0.1;
|
||||||
|
liveData->params.soc10odo[1] = liveData->params.soc10odo[2] + 30;
|
||||||
|
liveData->params.soc10time[1] = liveData->params.soc10time[2] + 900;
|
||||||
|
liveData->params.soc10ced[0] = liveData->params.soc10ced[1] + 2.9;
|
||||||
|
liveData->params.soc10cec[0] = liveData->params.soc10cec[1] + 0.5;
|
||||||
|
liveData->params.soc10odo[0] = liveData->params.soc10odo[1] + 15;
|
||||||
|
liveData->params.soc10time[0] = liveData->params.soc10time[1] + 900;
|
||||||
|
*/
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif //CARKIANIROPHEV_CPP
|
||||||
16
CarKiaNiroPhev.h
Normal file
16
CarKiaNiroPhev.h
Normal file
@@ -0,0 +1,16 @@
|
|||||||
|
#ifndef CARKIANIROPHEV_H
|
||||||
|
#define CARKIANIROPHEV_H
|
||||||
|
|
||||||
|
#include "CarInterface.h"
|
||||||
|
|
||||||
|
class CarKiaNiroPhev: public CarInterface {
|
||||||
|
|
||||||
|
protected:
|
||||||
|
|
||||||
|
public:
|
||||||
|
void activateCommandQueue() override;
|
||||||
|
void parseRowMerged() override;
|
||||||
|
void loadTestData() override;
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif
|
||||||
463
CarRenaultZoe.cpp
Normal file
463
CarRenaultZoe.cpp
Normal file
@@ -0,0 +1,463 @@
|
|||||||
|
#ifndef CARRENAULTZOE_CPP
|
||||||
|
#define CARRENAULTZOE_CPP
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <WString.h>
|
||||||
|
#include <string.h>
|
||||||
|
#include <sys/time.h>
|
||||||
|
#include "LiveData.h"
|
||||||
|
#include "CarRenaultZoe.h"
|
||||||
|
|
||||||
|
#define commandQueueCountRenaultZoe 18
|
||||||
|
#define commandQueueLoopFromRenaultZoe 11
|
||||||
|
|
||||||
|
/**
|
||||||
|
activateCommandQueue
|
||||||
|
*/
|
||||||
|
void CarRenaultZoe::activateCommandQueue() {
|
||||||
|
|
||||||
|
String commandQueueRenaultZoe[commandQueueCountRenaultZoe] = {
|
||||||
|
"AT Z", // Reset all
|
||||||
|
"AT I", // Print the version ID
|
||||||
|
"AT S0", // Printing of spaces on
|
||||||
|
"AT E0", // Echo off
|
||||||
|
"AT L0", // Linefeeds off
|
||||||
|
"AT SP 6", // Select protocol to ISO 15765-4 CAN (11 bit ID, 500 kbit/s)
|
||||||
|
//"AT AL", // Allow Long (>7 byte) messages
|
||||||
|
//"AT AR", // Automatically receive
|
||||||
|
//"AT H1", // Headers on (debug only)
|
||||||
|
//"AT D1", // Display of the DLC on
|
||||||
|
//"AT CAF0", // Automatic formatting off
|
||||||
|
////"AT AT0", // disabled adaptive timing
|
||||||
|
"AT DP",
|
||||||
|
"AT ST16", // reduced timeout to 1, orig.16
|
||||||
|
"atfcsd300010",
|
||||||
|
"atfcsm1", // Allow long messages
|
||||||
|
|
||||||
|
// Loop from (RENAULT ZOE)
|
||||||
|
|
||||||
|
// LBC Lithium battery controller
|
||||||
|
"ATSH79B",
|
||||||
|
"ATFCSH79B",
|
||||||
|
"2101",
|
||||||
|
"2103",
|
||||||
|
"2104",
|
||||||
|
"2141",
|
||||||
|
"2142",
|
||||||
|
"2161",
|
||||||
|
};
|
||||||
|
|
||||||
|
//
|
||||||
|
liveData->params.batModuleTempCount = 12; // 24, 12 is display limit
|
||||||
|
liveData->params.batteryTotalAvailableKWh = 28;
|
||||||
|
|
||||||
|
// Empty and fill command queue
|
||||||
|
for (int i = 0; i < 300; i++) {
|
||||||
|
liveData->commandQueue[i] = "";
|
||||||
|
}
|
||||||
|
for (int i = 0; i < commandQueueCountRenaultZoe; i++) {
|
||||||
|
liveData->commandQueue[i] = commandQueueRenaultZoe[i];
|
||||||
|
}
|
||||||
|
|
||||||
|
liveData->commandQueueLoopFrom = commandQueueLoopFromRenaultZoe;
|
||||||
|
liveData->commandQueueCount = commandQueueCountRenaultZoe;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
parseRowMerged
|
||||||
|
*/
|
||||||
|
void CarRenaultZoe::parseRowMerged() {
|
||||||
|
|
||||||
|
bool tempByte;
|
||||||
|
|
||||||
|
// LBC 79B
|
||||||
|
if (liveData->currentAtshRequest.equals("ATSH79B")) {
|
||||||
|
if (liveData->commandRequest.equals("2101")) {
|
||||||
|
liveData->params.batPowerAmp = liveData->hexToDecFromResponse(4, 8, 2, false) - 5000;
|
||||||
|
liveData->params.batPowerKw = (liveData->params.batPowerAmp * liveData->params.batVoltage) / 1000.0;
|
||||||
|
liveData->params.auxVoltage = liveData->hexToDecFromResponse(56, 60, 2, false) / 100.0;
|
||||||
|
liveData->params.availableChargePower = liveData->hexToDecFromResponse(84, 88, 2, false) / 100.0;
|
||||||
|
liveData->params.batCellMinV = liveData->hexToDecFromResponse(24, 28, 2, false) / 100.0;
|
||||||
|
liveData->params.batCellMaxV = liveData->hexToDecFromResponse(28, 32, 2, false) / 100.0;
|
||||||
|
}
|
||||||
|
if (liveData->commandRequest.equals("2103")) {
|
||||||
|
liveData->params.socPercPrevious = liveData->params.socPerc;
|
||||||
|
liveData->params.socPerc = liveData->hexToDecFromResponse(48, 52, 2, false) / 100.0;
|
||||||
|
}
|
||||||
|
if (liveData->commandRequest.equals("2104")) {
|
||||||
|
for (uint16_t i = 0; i < 12; i++) {
|
||||||
|
liveData->params.batModuleTempC[i] = liveData->hexToDecFromResponse(8 + ( i * 6), 10 + (i * 6), 1, false) - 40;
|
||||||
|
}
|
||||||
|
for (uint16_t i = 12; i < 24; i++) {
|
||||||
|
liveData->params.batModuleTempC[i] = liveData->hexToDecFromResponse(80 + ((i - 12) * 6), 82 + ((i - 12) * 6), 1, false) - 40;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (liveData->commandRequest.equals("2141")) {
|
||||||
|
for (int i = 0; i < 62; i++) {
|
||||||
|
liveData->params.cellVoltage[i] = liveData->hexToDecFromResponse(4 + (i * 4), 8 + (i * 4), 2, false) / 1000;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (liveData->commandRequest.equals("2142")) {
|
||||||
|
for (int i = 0; i < 34; i++) {
|
||||||
|
liveData->params.cellVoltage[i + 62] = liveData->hexToDecFromResponse(4 + (i * 4), 8 + (i * 4), 2, false) / 1000;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (liveData->commandRequest.equals("2161")) {
|
||||||
|
liveData->params.sohPerc = liveData->hexToDecFromResponse(18, 20, 2, false) / 2.0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/* niro
|
||||||
|
// ABS / ESP + AHB 7D1
|
||||||
|
if (liveData->currentAtshRequest.equals("ATSH7D1")) {
|
||||||
|
if (liveData->commandRequest.equals("22C101")) {
|
||||||
|
uint8_t driveMode = liveData->hexToDecFromResponse(22, 24, 1, false);
|
||||||
|
liveData->params.forwardDriveMode = (driveMode == 4);
|
||||||
|
liveData->params.reverseDriveMode = (driveMode == 2);
|
||||||
|
liveData->params.parkModeOrNeutral = (driveMode == 1);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// IGPM
|
||||||
|
if (liveData->currentAtshRequest.equals("ATSH770")) {
|
||||||
|
if (liveData->commandRequest.equals("22BC03")) {
|
||||||
|
tempByte = liveData->hexToDecFromResponse(16, 18, 1, false);
|
||||||
|
liveData->params.ignitionOnPrevious = liveData->params.ignitionOn;
|
||||||
|
liveData->params.ignitionOn = (bitRead(tempByte, 5) == 1);
|
||||||
|
if (liveData->params.ignitionOnPrevious && !liveData->params.ignitionOn)
|
||||||
|
liveData->params.automaticShutdownTimer = liveData->params.currentTime;
|
||||||
|
|
||||||
|
liveData->params.lightInfo = liveData->hexToDecFromResponse(18, 20, 1, false);
|
||||||
|
liveData->params.headLights = (bitRead(liveData->params.lightInfo, 5) == 1);
|
||||||
|
liveData->params.dayLights = (bitRead(liveData->params.lightInfo, 3) == 1);
|
||||||
|
}
|
||||||
|
if (liveData->commandRequest.equals("22BC06")) {
|
||||||
|
liveData->params.brakeLightInfo = liveData->hexToDecFromResponse(14, 16, 1, false);
|
||||||
|
liveData->params.brakeLights = (bitRead(liveData->params.brakeLightInfo, 5) == 1);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// VMCU 7E2
|
||||||
|
if (liveData->currentAtshRequest.equals("ATSH7E2")) {
|
||||||
|
if (liveData->commandRequest.equals("2101")) {
|
||||||
|
liveData->params.speedKmh = liveData->hexToDecFromResponse(32, 36, 2, false) * 0.0155; // / 100.0 *1.609 = real to gps is 1.750
|
||||||
|
if (liveData->params.speedKmh < -99 || liveData->params.speedKmh > 200)
|
||||||
|
liveData->params.speedKmh = 0;
|
||||||
|
}
|
||||||
|
if (liveData->commandRequest.equals("2102")) {
|
||||||
|
liveData->params.auxPerc = liveData->hexToDecFromResponse(50, 52, 1, false);
|
||||||
|
liveData->params.auxCurrentAmp = - liveData->hexToDecFromResponse(46, 50, 2, true) / 1000.0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Cluster module 7c6
|
||||||
|
if (liveData->currentAtshRequest.equals("ATSH7C6")) {
|
||||||
|
if (liveData->commandRequest.equals("22B002")) {
|
||||||
|
liveData->params.odoKm = liveData->decFromResponse(18, 24);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Aircon 7b3
|
||||||
|
if (liveData->currentAtshRequest.equals("ATSH7B3")) {
|
||||||
|
if (liveData->commandRequest.equals("220100")) {
|
||||||
|
liveData->params.indoorTemperature = (liveData->hexToDecFromResponse(16, 18, 1, false) / 2) - 40;
|
||||||
|
liveData->params.outdoorTemperature = (liveData->hexToDecFromResponse(18, 20, 1, false) / 2) - 40;
|
||||||
|
}
|
||||||
|
if (liveData->commandRequest.equals("220102") && liveData->responseRowMerged.substring(12, 14) == "00") {
|
||||||
|
liveData->params.coolantTemp1C = (liveData->hexToDecFromResponse(14, 16, 1, false) / 2) - 40;
|
||||||
|
liveData->params.coolantTemp2C = (liveData->hexToDecFromResponse(16, 18, 1, false) / 2) - 40;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// BMS 7e4
|
||||||
|
if (liveData->currentAtshRequest.equals("ATSH7E4")) {
|
||||||
|
if (liveData->commandRequest.equals("220101")) {
|
||||||
|
liveData->params.cumulativeEnergyChargedKWh = liveData->decFromResponse(82, 90) / 10.0;
|
||||||
|
if (liveData->params.cumulativeEnergyChargedKWhStart == -1)
|
||||||
|
liveData->params.cumulativeEnergyChargedKWhStart = liveData->params.cumulativeEnergyChargedKWh;
|
||||||
|
liveData->params.cumulativeEnergyDischargedKWh = liveData->decFromResponse(90, 98) / 10.0;
|
||||||
|
if (liveData->params.cumulativeEnergyDischargedKWhStart == -1)
|
||||||
|
liveData->params.cumulativeEnergyDischargedKWhStart = liveData->params.cumulativeEnergyDischargedKWh;
|
||||||
|
liveData->params.availableDischargePower = liveData->decFromResponse(20, 24) / 100.0;
|
||||||
|
//liveData->params.isolationResistanceKOhm = liveData->hexToDecFromResponse(118, 122, 2, true);
|
||||||
|
liveData->params.batFanStatus = liveData->hexToDecFromResponse(60, 62, 2, true);
|
||||||
|
liveData->params.batFanFeedbackHz = liveData->hexToDecFromResponse(62, 64, 2, true);
|
||||||
|
liveData->params.auxVoltage = liveData->hexToDecFromResponse(64, 66, 2, true) / 10.0;
|
||||||
|
liveData->params.batVoltage = liveData->hexToDecFromResponse(30, 34, 2, false) / 10.0;
|
||||||
|
if (liveData->params.batPowerKw < 0) // Reset charging start time
|
||||||
|
liveData->params.chargingStartTime = liveData->params.currentTime;
|
||||||
|
liveData->params.batPowerKwh100 = liveData->params.batPowerKw / liveData->params.speedKmh * 100;
|
||||||
|
liveData->params.batModuleTempC[0] = liveData->hexToDecFromResponse(38, 40, 1, true);
|
||||||
|
liveData->params.batModuleTempC[1] = liveData->hexToDecFromResponse(40, 42, 1, true);
|
||||||
|
liveData->params.batModuleTempC[2] = liveData->hexToDecFromResponse(42, 44, 1, true);
|
||||||
|
liveData->params.batModuleTempC[3] = liveData->hexToDecFromResponse(44, 46, 1, true);
|
||||||
|
liveData->params.motorRpm = liveData->hexToDecFromResponse(112, 116, 2, false);
|
||||||
|
|
||||||
|
// This is more accurate than min/max from BMS. It's required to detect kona/eniro cold gates (min 15C is needed > 43kW charging, min 25C is needed > 58kW charging)
|
||||||
|
liveData->params.batMinC = liveData->params.batMaxC = liveData->params.batModuleTempC[0];
|
||||||
|
for (uint16_t i = 1; i < liveData->params.batModuleTempCount; i++) {
|
||||||
|
if (liveData->params.batModuleTempC[i] < liveData->params.batMinC)
|
||||||
|
liveData->params.batMinC = liveData->params.batModuleTempC[i];
|
||||||
|
if (liveData->params.batModuleTempC[i] > liveData->params.batMaxC)
|
||||||
|
liveData->params.batMaxC = liveData->params.batModuleTempC[i];
|
||||||
|
}
|
||||||
|
liveData->params.batTempC = liveData->params.batMinC;
|
||||||
|
|
||||||
|
liveData->params.batInletC = liveData->hexToDecFromResponse(50, 52, 1, true);
|
||||||
|
if (liveData->params.speedKmh < 10 && liveData->params.batPowerKw >= 1 && liveData->params.socPerc > 0 && liveData->params.socPerc <= 100) {
|
||||||
|
if ( liveData->params.chargingGraphMinKw[int(liveData->params.socPerc)] < 0 || liveData->params.batPowerKw < liveData->params.chargingGraphMinKw[int(liveData->params.socPerc)])
|
||||||
|
liveData->params.chargingGraphMinKw[int(liveData->params.socPerc)] = liveData->params.batPowerKw;
|
||||||
|
if ( liveData->params.chargingGraphMaxKw[int(liveData->params.socPerc)] < 0 || liveData->params.batPowerKw > liveData->params.chargingGraphMaxKw[int(liveData->params.socPerc)])
|
||||||
|
liveData->params.chargingGraphMaxKw[int(liveData->params.socPerc)] = liveData->params.batPowerKw;
|
||||||
|
liveData->params.chargingGraphBatMinTempC[int(liveData->params.socPerc)] = liveData->params.batMinC;
|
||||||
|
liveData->params.chargingGraphBatMaxTempC[int(liveData->params.socPerc)] = liveData->params.batMaxC;
|
||||||
|
liveData->params.chargingGraphHeaterTempC[int(liveData->params.socPerc)] = liveData->params.batHeaterC;
|
||||||
|
liveData->params.chargingGraphWaterCoolantTempC[int(liveData->params.socPerc)] = liveData->params.coolingWaterTempC;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
// BMS 7e4
|
||||||
|
if (liveData->commandRequest.equals("220102") && liveData->responseRowMerged.substring(12, 14) == "FF") {
|
||||||
|
for (int i = 0; i < 32; i++) {
|
||||||
|
liveData->params.cellVoltage[i] = liveData->hexToDecFromResponse(14 + (i * 2), 14 + (i * 2) + 2, 1, false) / 50;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
// BMS 7e4
|
||||||
|
if (liveData->commandRequest.equals("220103")) {
|
||||||
|
for (int i = 0; i < 32; i++) {
|
||||||
|
liveData->params.cellVoltage[32 + i] = liveData->hexToDecFromResponse(14 + (i * 2), 14 + (i * 2) + 2, 1, false) / 50;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
// BMS 7e4
|
||||||
|
if (liveData->commandRequest.equals("220104")) {
|
||||||
|
for (int i = 0; i < 32; i++) {
|
||||||
|
liveData->params.cellVoltage[64 + i] = liveData->hexToDecFromResponse(14 + (i * 2), 14 + (i * 2) + 2, 1, false) / 50;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
// BMS 7e4
|
||||||
|
if (liveData->commandRequest.equals("220105")) {
|
||||||
|
liveData->params.socPercPrevious = liveData->params.socPerc;
|
||||||
|
liveData->params.sohPerc = liveData->hexToDecFromResponse(56, 60, 2, false) / 10.0;
|
||||||
|
liveData->params.socPerc = liveData->hexToDecFromResponse(68, 70, 1, false) / 2.0;
|
||||||
|
|
||||||
|
// Soc10ced table, record x0% CEC/CED table (ex. 90%->89%, 80%->79%)
|
||||||
|
if (liveData->params.socPercPrevious - liveData->params.socPerc > 0) {
|
||||||
|
byte index = (int(liveData->params.socPerc) == 4) ? 0 : (int)(liveData->params.socPerc / 10) + 1;
|
||||||
|
if ((int(liveData->params.socPerc) % 10 == 9 || int(liveData->params.socPerc) == 4) && liveData->params.soc10ced[index] == -1) {
|
||||||
|
liveData->params.soc10ced[index] = liveData->params.cumulativeEnergyDischargedKWh;
|
||||||
|
liveData->params.soc10cec[index] = liveData->params.cumulativeEnergyChargedKWh;
|
||||||
|
liveData->params.soc10odo[index] = liveData->params.odoKm;
|
||||||
|
liveData->params.soc10time[index] = liveData->params.currentTime;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
liveData->params.bmsUnknownTempA = liveData->hexToDecFromResponse(30, 32, 1, true);
|
||||||
|
liveData->params.batHeaterC = liveData->hexToDecFromResponse(52, 54, 1, true);
|
||||||
|
liveData->params.bmsUnknownTempB = liveData->hexToDecFromResponse(82, 84, 1, true);
|
||||||
|
//
|
||||||
|
for (int i = 30; i < 32; i++) { // ai/aj position
|
||||||
|
liveData->params.cellVoltage[96 - 30 + i] = liveData->hexToDecFromResponse(14 + (i * 2), 14 + (i * 2) + 2, 1, false) / 50;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
// BMS 7e4
|
||||||
|
if (liveData->commandRequest.equals("220106")) {
|
||||||
|
liveData->params.coolingWaterTempC = liveData->hexToDecFromResponse(14, 16, 1, false);
|
||||||
|
liveData->params.bmsUnknownTempC = liveData->hexToDecFromResponse(18, 20, 1, true);
|
||||||
|
liveData->params.bmsUnknownTempD = liveData->hexToDecFromResponse(46, 48, 1, true);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// TPMS 7a0
|
||||||
|
if (liveData->currentAtshRequest.equals("ATSH7A0")) {
|
||||||
|
if (liveData->commandRequest.equals("22c00b")) {
|
||||||
|
liveData->params.tireFrontLeftPressureBar = liveData->hexToDecFromResponse(14, 16, 2, false) / 72.51886900361; // === OK Valid *0.2 / 14.503773800722
|
||||||
|
liveData->params.tireFrontRightPressureBar = liveData->hexToDecFromResponse(22, 24, 2, false) / 72.51886900361; // === OK Valid *0.2 / 14.503773800722
|
||||||
|
liveData->params.tireRearRightPressureBar = liveData->hexToDecFromResponse(30, 32, 2, false) / 72.51886900361; // === OK Valid *0.2 / 14.503773800722
|
||||||
|
liveData->params.tireRearLeftPressureBar = liveData->hexToDecFromResponse(38, 40, 2, false) / 72.51886900361; // === OK Valid *0.2 / 14.503773800722
|
||||||
|
liveData->params.tireFrontLeftTempC = liveData->hexToDecFromResponse(16, 18, 2, false) - 50; // === OK Valid
|
||||||
|
liveData->params.tireFrontRightTempC = liveData->hexToDecFromResponse(24, 26, 2, false) - 50; // === OK Valid
|
||||||
|
liveData->params.tireRearRightTempC = liveData->hexToDecFromResponse(32, 34, 2, false) - 50; // === OK Valid
|
||||||
|
liveData->params.tireRearLeftTempC = liveData->hexToDecFromResponse(40, 42, 2, false) - 50; // === OK Valid
|
||||||
|
}
|
||||||
|
}
|
||||||
|
*/
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
loadTestData
|
||||||
|
*/
|
||||||
|
void CarRenaultZoe::loadTestData() {
|
||||||
|
|
||||||
|
/// LBC 79B
|
||||||
|
liveData->currentAtshRequest = "ATSH79B";
|
||||||
|
liveData->commandRequest = "2101";
|
||||||
|
liveData->responseRowMerged = "6101134D138600000000000000000000000009980D610FB120D0000005420000000000000004ECB20000074B2927100000000000000000";
|
||||||
|
parseRowMerged();
|
||||||
|
liveData->commandRequest = "2103";
|
||||||
|
liveData->responseRowMerged = "610301770D010D740000000001750174000000FFFF07D0050D410000030000000000";
|
||||||
|
parseRowMerged();
|
||||||
|
liveData->commandRequest = "2104";
|
||||||
|
liveData->responseRowMerged = "61040B9D290B9F290B9D290B99290B9E290B98290B8A2A0B842A0BA0290B9B290B9A290B9629FFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFFF29292A000000000000";
|
||||||
|
parseRowMerged();
|
||||||
|
liveData->commandRequest = "2141";
|
||||||
|
liveData->responseRowMerged = "61410E930E950E900E930E930E950E950E930E970E940E970E970E950E940E940E930E970E920E930E8F0E900E8E0E8C0E920E970E920E940E940E930E950E950E940E970E970E950E970E940E950E950E990E940E9A0E8E0E900E990E950E900E990E980E950E940E970E970E950E940E980E970E920E920E940E950E93000000000000";
|
||||||
|
parseRowMerged();
|
||||||
|
liveData->commandRequest = "2142";
|
||||||
|
liveData->responseRowMerged = "61420E920E940E970E930E920E970E940E950E950E980E920E900E8F0E8F0E920E900E920E940E9B0E980E950E940E950E930E970E980E980E950E950E930E970E950E950E978BFA8C200000";
|
||||||
|
parseRowMerged();
|
||||||
|
liveData->commandRequest = "2161";
|
||||||
|
liveData->responseRowMerged = "6161000AA820C8C8C8C2C2000153B400004669FF";
|
||||||
|
parseRowMerged();
|
||||||
|
|
||||||
|
|
||||||
|
/*
|
||||||
|
niro
|
||||||
|
/// IGPM
|
||||||
|
liveData->currentAtshRequest = "ATSH770";
|
||||||
|
// 22BC03
|
||||||
|
liveData->commandRequest = "22BC03";
|
||||||
|
liveData->responseRowMerged = "62BC03FDEE7C730A600000AAAA";
|
||||||
|
parseRowMerged();
|
||||||
|
|
||||||
|
// ABS / ESP + AHB ATSH7D1
|
||||||
|
liveData->currentAtshRequest = "ATSH7D1";
|
||||||
|
// 2101
|
||||||
|
liveData->commandRequest = "22C101";
|
||||||
|
liveData->responseRowMerged = "62C1015FD7E7D0FFFF00FF04D0D400000000FF7EFF0030F5010000FFFF7F6307F207FE05FF00FF3FFFFFAAAAAAAAAAAA";
|
||||||
|
parseRowMerged();
|
||||||
|
|
||||||
|
// VMCU ATSH7E2
|
||||||
|
liveData->currentAtshRequest = "ATSH7E2";
|
||||||
|
// 2101
|
||||||
|
liveData->commandRequest = "2101";
|
||||||
|
liveData->responseRowMerged = "6101FFF8000009285A3B0648030000B4179D763404080805000000";
|
||||||
|
parseRowMerged();
|
||||||
|
// 2102
|
||||||
|
liveData->commandRequest = "2102";
|
||||||
|
liveData->responseRowMerged = "6102F8FFFC000101000000840FBF83BD33270680953033757F59291C76000001010100000007000000";
|
||||||
|
liveData->responseRowMerged = "6102F8FFFC000101000000931CC77F4C39040BE09BA7385D8158832175000001010100000007000000";
|
||||||
|
parseRowMerged();
|
||||||
|
|
||||||
|
// "ATSH7DF",
|
||||||
|
liveData->currentAtshRequest = "ATSH7DF";
|
||||||
|
// 2106
|
||||||
|
liveData->commandRequest = "2106";
|
||||||
|
liveData->responseRowMerged = "6106FFFF800000000000000200001B001C001C000600060006000E000000010000000000000000013D013D013E013E00";
|
||||||
|
parseRowMerged();
|
||||||
|
|
||||||
|
// AIRCON / ACU ATSH7B3
|
||||||
|
liveData->currentAtshRequest = "ATSH7B3";
|
||||||
|
// 220100
|
||||||
|
liveData->commandRequest = "220100";
|
||||||
|
liveData->responseRowMerged = "6201007E5027C8FF7F765D05B95AFFFF5AFF11FFFFFFFFFFFF6AFFFF2DF0757630FFFF00FFFF000000";
|
||||||
|
liveData->responseRowMerged = "6201007E5027C8FF867C58121010FFFF10FF8EFFFFFFFFFFFF10FFFF0DF0617900FFFF01FFFF000000";
|
||||||
|
parseRowMerged();
|
||||||
|
|
||||||
|
// BMS ATSH7E4
|
||||||
|
liveData->currentAtshRequest = "ATSH7E4";
|
||||||
|
// 220101
|
||||||
|
liveData->commandRequest = "220101";
|
||||||
|
liveData->responseRowMerged = "620101FFF7E7FF99000000000300B10EFE120F11100F12000018C438C30B00008400003864000035850000153A00001374000647010D017F0BDA0BDA03E8";
|
||||||
|
liveData->responseRowMerged = "620101FFF7E7FFB3000000000300120F9B111011101011000014CC38CB3B00009100003A510000367C000015FB000013D3000690250D018E0000000003E8";
|
||||||
|
parseRowMerged();
|
||||||
|
// 220102
|
||||||
|
liveData->commandRequest = "220102";
|
||||||
|
liveData->responseRowMerged = "620102FFFFFFFFCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBAAAA";
|
||||||
|
parseRowMerged();
|
||||||
|
// 220103
|
||||||
|
liveData->commandRequest = "220103";
|
||||||
|
liveData->responseRowMerged = "620103FFFFFFFFCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCACBCACACFCCCBCBCBCBCBCBCBCBAAAA";
|
||||||
|
parseRowMerged();
|
||||||
|
// 220104
|
||||||
|
liveData->commandRequest = "220104";
|
||||||
|
liveData->responseRowMerged = "620104FFFFFFFFCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBCBAAAA";
|
||||||
|
parseRowMerged();
|
||||||
|
// 220105
|
||||||
|
liveData->commandRequest = "220105";
|
||||||
|
liveData->responseRowMerged = "620105003fff9000000000000000000F8A86012B4946500101500DAC03E800000000AC0000C7C701000F00000000AAAA";
|
||||||
|
liveData->responseRowMerged = "620105003FFF90000000000000000014918E012927465000015013BB03E800000000BB0000CBCB01001300000000AAAA";
|
||||||
|
parseRowMerged();
|
||||||
|
// 220106
|
||||||
|
liveData->commandRequest = "220106";
|
||||||
|
liveData->responseRowMerged = "620106FFFFFFFF14001A00240000003A7C86B4B30000000928EA00";
|
||||||
|
parseRowMerged();
|
||||||
|
|
||||||
|
// BCM / TPMS ATSH7A0
|
||||||
|
liveData->currentAtshRequest = "ATSH7A0";
|
||||||
|
// 22c00b
|
||||||
|
liveData->commandRequest = "22c00b";
|
||||||
|
liveData->responseRowMerged = "62C00BFFFF0000B93D0100B43E0100B43D0100BB3C0100AAAAAAAA";
|
||||||
|
parseRowMerged();
|
||||||
|
|
||||||
|
// ATSH7C6
|
||||||
|
liveData->currentAtshRequest = "ATSH7C6";
|
||||||
|
// 22b002
|
||||||
|
liveData->commandRequest = "22b002";
|
||||||
|
liveData->responseRowMerged = "62B002E0000000FFB400330B0000000000000000";
|
||||||
|
parseRowMerged();
|
||||||
|
|
||||||
|
liveData->params.batModuleTempC[0] = 28;
|
||||||
|
liveData->params.batModuleTempC[1] = 29;
|
||||||
|
liveData->params.batModuleTempC[2] = 28;
|
||||||
|
liveData->params.batModuleTempC[3] = 30;
|
||||||
|
|
||||||
|
// This is more accurate than min/max from BMS. It's required to detect kona/eniro cold gates (min 15C is needed > 43kW charging, min 25C is needed > 58kW charging)
|
||||||
|
liveData->params.batMinC = liveData->params.batMaxC = liveData->params.batModuleTempC[0];
|
||||||
|
for (uint16_t i = 1; i < liveData->params.batModuleTempCount; i++) {
|
||||||
|
if (liveData->params.batModuleTempC[i] < liveData->params.batMinC)
|
||||||
|
liveData->params.batMinC = liveData->params.batModuleTempC[i];
|
||||||
|
if (liveData->params.batModuleTempC[i] > liveData->params.batMaxC)
|
||||||
|
liveData->params.batMaxC = liveData->params.batModuleTempC[i];
|
||||||
|
}
|
||||||
|
liveData->params.batTempC = liveData->params.batMinC;
|
||||||
|
|
||||||
|
|
||||||
|
//
|
||||||
|
liveData->params.soc10ced[10] = 2200;
|
||||||
|
liveData->params.soc10cec[10] = 2500;
|
||||||
|
liveData->params.soc10odo[10] = 13000;
|
||||||
|
liveData->params.soc10time[10] = 13000;
|
||||||
|
liveData->params.soc10ced[9] = liveData->params.soc10ced[10] + 6.4;
|
||||||
|
liveData->params.soc10cec[9] = liveData->params.soc10cec[10] + 0;
|
||||||
|
liveData->params.soc10odo[9] = liveData->params.soc10odo[10] + 30;
|
||||||
|
liveData->params.soc10time[9] = liveData->params.soc10time[10] + 900;
|
||||||
|
liveData->params.soc10ced[8] = liveData->params.soc10ced[9] + 6.8;
|
||||||
|
liveData->params.soc10cec[8] = liveData->params.soc10cec[9] + 0;
|
||||||
|
liveData->params.soc10odo[8] = liveData->params.soc10odo[9] + 30;
|
||||||
|
liveData->params.soc10time[8] = liveData->params.soc10time[9] + 900;
|
||||||
|
liveData->params.soc10ced[7] = liveData->params.soc10ced[8] + 7.2;
|
||||||
|
liveData->params.soc10cec[7] = liveData->params.soc10cec[8] + 0.6;
|
||||||
|
liveData->params.soc10odo[7] = liveData->params.soc10odo[8] + 30;
|
||||||
|
liveData->params.soc10time[7] = liveData->params.soc10time[8] + 900;
|
||||||
|
liveData->params.soc10ced[6] = liveData->params.soc10ced[7] + 6.7;
|
||||||
|
liveData->params.soc10cec[6] = liveData->params.soc10cec[7] + 0;
|
||||||
|
liveData->params.soc10odo[6] = liveData->params.soc10odo[7] + 30;
|
||||||
|
liveData->params.soc10time[6] = liveData->params.soc10time[7] + 900;
|
||||||
|
liveData->params.soc10ced[5] = liveData->params.soc10ced[6] + 6.7;
|
||||||
|
liveData->params.soc10cec[5] = liveData->params.soc10cec[6] + 0;
|
||||||
|
liveData->params.soc10odo[5] = liveData->params.soc10odo[6] + 30;
|
||||||
|
liveData->params.soc10time[5] = liveData->params.soc10time[6] + 900;
|
||||||
|
liveData->params.soc10ced[4] = liveData->params.soc10ced[5] + 6.4;
|
||||||
|
liveData->params.soc10cec[4] = liveData->params.soc10cec[5] + 0.3;
|
||||||
|
liveData->params.soc10odo[4] = liveData->params.soc10odo[5] + 30;
|
||||||
|
liveData->params.soc10time[4] = liveData->params.soc10time[5] + 900;
|
||||||
|
liveData->params.soc10ced[3] = liveData->params.soc10ced[4] + 6.4;
|
||||||
|
liveData->params.soc10cec[3] = liveData->params.soc10cec[4] + 0;
|
||||||
|
liveData->params.soc10odo[3] = liveData->params.soc10odo[4] + 30;
|
||||||
|
liveData->params.soc10time[3] = liveData->params.soc10time[4] + 900;
|
||||||
|
liveData->params.soc10ced[2] = liveData->params.soc10ced[3] + 5.4;
|
||||||
|
liveData->params.soc10cec[2] = liveData->params.soc10cec[3] + 0.1;
|
||||||
|
liveData->params.soc10odo[2] = liveData->params.soc10odo[3] + 30;
|
||||||
|
liveData->params.soc10time[2] = liveData->params.soc10time[3] + 900;
|
||||||
|
liveData->params.soc10ced[1] = liveData->params.soc10ced[2] + 6.2;
|
||||||
|
liveData->params.soc10cec[1] = liveData->params.soc10cec[2] + 0.1;
|
||||||
|
liveData->params.soc10odo[1] = liveData->params.soc10odo[2] + 30;
|
||||||
|
liveData->params.soc10time[1] = liveData->params.soc10time[2] + 900;
|
||||||
|
liveData->params.soc10ced[0] = liveData->params.soc10ced[1] + 2.9;
|
||||||
|
liveData->params.soc10cec[0] = liveData->params.soc10cec[1] + 0.5;
|
||||||
|
liveData->params.soc10odo[0] = liveData->params.soc10odo[1] + 15;
|
||||||
|
liveData->params.soc10time[0] = liveData->params.soc10time[1] + 900;
|
||||||
|
*/
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif // CARRENAULTZOE_CPP
|
||||||
16
CarRenaultZoe.h
Normal file
16
CarRenaultZoe.h
Normal file
@@ -0,0 +1,16 @@
|
|||||||
|
#ifndef CARRENAULTZOE_H
|
||||||
|
#define CARRENAULTZOE_H
|
||||||
|
|
||||||
|
#include "CarInterface.h"
|
||||||
|
|
||||||
|
class CarRenaultZoe : public CarInterface {
|
||||||
|
|
||||||
|
protected:
|
||||||
|
|
||||||
|
public:
|
||||||
|
void activateCommandQueue() override;
|
||||||
|
void parseRowMerged() override;
|
||||||
|
void loadTestData() override;
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif // CARRENAULTZOE_H
|
||||||
13
CommInterface.cpp
Normal file
13
CommInterface.cpp
Normal file
@@ -0,0 +1,13 @@
|
|||||||
|
#ifndef COMMINTERFACE_CPP
|
||||||
|
#define COMMINTERFACE_CPP
|
||||||
|
|
||||||
|
#include "CommInterface.h"
|
||||||
|
//#include "BoardInterface.h"
|
||||||
|
#include "LiveData.h"
|
||||||
|
|
||||||
|
void CommInterface::initComm(LiveData* pLiveData/*, BoardInterface* pBoard*/) {
|
||||||
|
liveData = pLiveData;
|
||||||
|
//board = pBoard;
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif // COMMINTERFACE_CPP
|
||||||
19
CommInterface.h
Normal file
19
CommInterface.h
Normal file
@@ -0,0 +1,19 @@
|
|||||||
|
#ifndef COMMINTERFACE_H
|
||||||
|
#define COMMINTERFACE_H
|
||||||
|
|
||||||
|
#include "LiveData.h"
|
||||||
|
//#include "BoardInterface.h"
|
||||||
|
|
||||||
|
class CommInterface {
|
||||||
|
|
||||||
|
protected:
|
||||||
|
LiveData* liveData;
|
||||||
|
//BoardInterface* board;
|
||||||
|
public:
|
||||||
|
void initComm(LiveData* pLiveData/*, BoardInterface* pBoard**/);
|
||||||
|
virtual void connectDevice() = 0;
|
||||||
|
virtual void disconnectDevice() = 0;
|
||||||
|
virtual void scanDevices() = 0;
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif // COMMINTERFACE_H
|
||||||
29
CommObd2Ble4.cpp
Normal file
29
CommObd2Ble4.cpp
Normal file
@@ -0,0 +1,29 @@
|
|||||||
|
#ifndef COMMOBD2BLE4_CPP
|
||||||
|
#define COMMOBD2BLE4_CPP
|
||||||
|
|
||||||
|
#include <BLEDevice.h>
|
||||||
|
#include "CommObd2Ble4.h"
|
||||||
|
#include "LiveData.h"
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Connect ble4 adapter
|
||||||
|
*/
|
||||||
|
void CommObd2Ble4::connectDevice() {
|
||||||
|
Serial.println("COMM connectDevice");
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Disconnect device
|
||||||
|
*/
|
||||||
|
void CommObd2Ble4::disconnectDevice() {
|
||||||
|
Serial.println("COMM disconnectDevice");
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Scan device list
|
||||||
|
*/
|
||||||
|
void CommObd2Ble4::scanDevices() {
|
||||||
|
Serial.println("COMM scanDevices");
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif // COMMOBD2BLE4_CPP
|
||||||
17
CommObd2Ble4.h
Normal file
17
CommObd2Ble4.h
Normal file
@@ -0,0 +1,17 @@
|
|||||||
|
#ifndef COMMOBD2BLE4_H
|
||||||
|
#define COMMOBD2BLE4_H
|
||||||
|
|
||||||
|
#include "LiveData.h"
|
||||||
|
#include "CommInterface.h"
|
||||||
|
|
||||||
|
class CommObd2Ble4 : public CommInterface {
|
||||||
|
|
||||||
|
protected:
|
||||||
|
uint32_t PIN = 1234;
|
||||||
|
public:
|
||||||
|
void connectDevice() override;
|
||||||
|
void disconnectDevice() override;
|
||||||
|
void scanDevices() override;
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif // COMMOBD2BLE4_H
|
||||||
7
CommObd2Can.cpp
Normal file
7
CommObd2Can.cpp
Normal file
@@ -0,0 +1,7 @@
|
|||||||
|
#ifndef COMMINTERFACE_CPP
|
||||||
|
#define COMMINTERFACE_CPP
|
||||||
|
|
||||||
|
#include "CommInterface.h"
|
||||||
|
#include "LiveData.h"
|
||||||
|
|
||||||
|
#endif // COMMINTERFACE_CPP
|
||||||
12
CommObd2Can.h
Normal file
12
CommObd2Can.h
Normal file
@@ -0,0 +1,12 @@
|
|||||||
|
#ifndef COMMOBD2CAN_H
|
||||||
|
#define COMMOBD2CAN_H
|
||||||
|
|
||||||
|
#include "LiveData.h"
|
||||||
|
|
||||||
|
class CommObd2Can : public CommInterface {
|
||||||
|
|
||||||
|
protected:
|
||||||
|
public:
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif // COMMOBD2CAN_H
|
||||||
@@ -12,16 +12,24 @@ https://docs.google.com/document/d/1nEezrtXY-8X6mQ1hiZVWDjBVse1sXQg1SlnizaRmJwU/
|
|||||||
|
|
||||||
## Installation from sources
|
## Installation from sources
|
||||||
- install arduino IDE + ESP32 support
|
- install arduino IDE + ESP32 support
|
||||||
- https://github.com/Bodmer/TFT_eSPI - display library
|
|
||||||
- Configure TFT eSPI
|
Required libraries
|
||||||
W:\Documents\Arduino\libraries\TFT_eSP\User_Setup_Select.h
|
|
||||||
|
- ArduinoJson
|
||||||
|
- TFT_eSPI
|
||||||
|
- ESP32_AnalogWrite
|
||||||
|
- esp32-micro-sdcard (arduino-cli)
|
||||||
|
- TinyGPSPlus (m5stack GPS)
|
||||||
|
|
||||||
|
Configure TFT eSPI
|
||||||
|
|
||||||
|
W:\Documents\Arduino\libraries\TFT_eSP\User_Setup_Select.h
|
||||||
```
|
```
|
||||||
// Comment
|
// Comment
|
||||||
//#include <User_Setup.h> // Default setup is root library folder
|
//#include <User_Setup.h> // Default setup is root library folder
|
||||||
// And uncomment
|
// And uncomment
|
||||||
#include <User_Setups/Setup22_TTGO_T4_v1.3.h> // Setup file for ESP32 and TTGO T4 version 1.3
|
#include <User_Setups/Setup22_TTGO_T4_v1.3.h> // Setup file for ESP32 and TTGO T4 version 1.3
|
||||||
```
|
```
|
||||||
|
|
||||||
My configuration
|
My configuration
|
||||||
- Board ESP32 Dev module
|
- Board ESP32 Dev module
|
||||||
- Upload speed 921600
|
- Upload speed 921600
|
||||||
|
|||||||
199
LiveData.cpp
199
LiveData.cpp
@@ -10,95 +10,113 @@
|
|||||||
*/
|
*/
|
||||||
void LiveData::initParams() {
|
void LiveData::initParams() {
|
||||||
|
|
||||||
this->params.automaticShutdownTimer = 0;
|
params.automaticShutdownTimer = 0;
|
||||||
#ifdef SIM800L_ENABLED
|
// SIM
|
||||||
this->params.lastDataSent = 0;
|
params.lastDataSent = 0;
|
||||||
this->params.sim800l_enabled = false;
|
params.sim800l_enabled = false;
|
||||||
#endif //SIM800L_ENABLED
|
// SD card
|
||||||
this->params.ignitionOn = false;
|
params.sdcardInit = false;
|
||||||
this->params.ignitionOnPrevious = false;
|
params.sdcardRecording = false;
|
||||||
this->params.chargingStartTime = this->params.currentTime = 0;
|
String tmpStr = "";
|
||||||
this->params.lightInfo = 0;
|
tmpStr.toCharArray(params.sdcardFilename, tmpStr.length() + 1);
|
||||||
this->params.headLights = false;
|
params.sdcardCanNotify = false;
|
||||||
this->params.dayLights = false;
|
// Gps
|
||||||
this->params.brakeLights = false;
|
params.currTimeSyncWithGps = false;
|
||||||
this->params.brakeLightInfo = 0;
|
params.gpsLat = -1;
|
||||||
this->params.forwardDriveMode = false;
|
params.gpsLon = -1;
|
||||||
this->params.reverseDriveMode = false;
|
params.gpsSat = 0;
|
||||||
this->params.parkModeOrNeutral = false;
|
params.gpsAlt = -1;
|
||||||
this->params.espState = 0;
|
// Car data
|
||||||
this->params.speedKmh = -1;
|
params.ignitionOn = false;
|
||||||
this->params.motorRpm = -1;
|
params.ignitionOnPrevious = false;
|
||||||
this->params.odoKm = -1;
|
params.operationTimeSec = 0;
|
||||||
this->params.socPerc = -1;
|
params.chargingStartTime = params.currentTime = 0;
|
||||||
this->params.socPercPrevious = -1;
|
params.lightInfo = 0;
|
||||||
this->params.sohPerc = -1;
|
params.headLights = false;
|
||||||
this->params.cumulativeEnergyChargedKWh = -1;
|
params.dayLights = false;
|
||||||
this->params.cumulativeEnergyChargedKWhStart = -1;
|
params.brakeLights = false;
|
||||||
this->params.cumulativeEnergyDischargedKWh = -1;
|
params.brakeLightInfo = 0;
|
||||||
this->params.cumulativeEnergyDischargedKWhStart = -1;
|
params.forwardDriveMode = false;
|
||||||
this->params.availableChargePower = -1;
|
params.reverseDriveMode = false;
|
||||||
this->params.availableDischargePower = -1;
|
params.parkModeOrNeutral = false;
|
||||||
this->params.isolationResistanceKOhm = -1;
|
params.espState = 0;
|
||||||
this->params.batPowerAmp = -1;
|
params.speedKmh = -1;
|
||||||
this->params.batPowerKw = -1;
|
params.motorRpm = -1;
|
||||||
this->params.batPowerKwh100 = -1;
|
params.odoKm = -1;
|
||||||
this->params.batVoltage = -1;
|
params.socPerc = -1;
|
||||||
this->params.batCellMinV = -1;
|
params.socPercPrevious = -1;
|
||||||
this->params.batCellMaxV = -1;
|
params.sohPerc = -1;
|
||||||
this->params.batTempC = -1;
|
params.cumulativeEnergyChargedKWh = -1;
|
||||||
this->params.batHeaterC = -1;
|
params.cumulativeEnergyChargedKWhStart = -1;
|
||||||
this->params.batInletC = -1;
|
params.cumulativeEnergyDischargedKWh = -1;
|
||||||
this->params.batFanStatus = -1;
|
params.cumulativeEnergyDischargedKWhStart = -1;
|
||||||
this->params.batFanFeedbackHz = -1;
|
params.availableChargePower = -1;
|
||||||
this->params.batMinC = -1;
|
params.availableDischargePower = -1;
|
||||||
this->params.batMaxC = -1;
|
params.isolationResistanceKOhm = -1;
|
||||||
|
params.batPowerAmp = -1;
|
||||||
|
params.batPowerKw = -1;
|
||||||
|
params.batPowerKwh100 = -1;
|
||||||
|
params.batVoltage = -1;
|
||||||
|
params.batCellMinV = -1;
|
||||||
|
params.batCellMaxV = -1;
|
||||||
|
params.batTempC = -1;
|
||||||
|
params.batHeaterC = -1;
|
||||||
|
params.batInletC = -1;
|
||||||
|
params.batFanStatus = -1;
|
||||||
|
params.batFanFeedbackHz = -1;
|
||||||
|
params.batMinC = -1;
|
||||||
|
params.batMaxC = -1;
|
||||||
for (int i = 0; i < 12; i++) {
|
for (int i = 0; i < 12; i++) {
|
||||||
this->params.batModuleTempC[i] = 0;
|
params.batModuleTempC[i] = 0;
|
||||||
}
|
}
|
||||||
this->params.batModuleTempC[0] = -1;
|
params.batModuleTempC[0] = -1;
|
||||||
this->params.batModuleTempC[1] = -1;
|
params.batModuleTempC[1] = -1;
|
||||||
this->params.batModuleTempC[2] = -1;
|
params.batModuleTempC[2] = -1;
|
||||||
this->params.batModuleTempC[3] = -1;
|
params.batModuleTempC[3] = -1;
|
||||||
this->params.coolingWaterTempC = -1;
|
params.coolingWaterTempC = -1;
|
||||||
this->params.coolantTemp1C = -1;
|
params.coolantTemp1C = -1;
|
||||||
this->params.coolantTemp2C = -1;
|
params.coolantTemp2C = -1;
|
||||||
this->params.bmsUnknownTempA = -1;
|
params.bmsUnknownTempA = -1;
|
||||||
this->params.bmsUnknownTempB = -1;
|
params.bmsUnknownTempB = -1;
|
||||||
this->params.bmsUnknownTempC = -1;
|
params.bmsUnknownTempC = -1;
|
||||||
this->params.bmsUnknownTempD = -1;
|
params.bmsUnknownTempD = -1;
|
||||||
this->params.auxPerc = -1;
|
params.auxPerc = -1;
|
||||||
this->params.auxCurrentAmp = -1;
|
params.auxCurrentAmp = -1;
|
||||||
this->params.auxVoltage = -1;
|
params.auxVoltage = -1;
|
||||||
this->params.indoorTemperature = -1;
|
params.indoorTemperature = -1;
|
||||||
this->params.outdoorTemperature = -1;
|
params.outdoorTemperature = -1;
|
||||||
this->params.tireFrontLeftTempC = -1;
|
params.tireFrontLeftTempC = -1;
|
||||||
this->params.tireFrontLeftPressureBar = -1;
|
params.tireFrontLeftPressureBar = -1;
|
||||||
this->params.tireFrontRightTempC = -1;
|
params.tireFrontRightTempC = -1;
|
||||||
this->params.tireFrontRightPressureBar = -1;
|
params.tireFrontRightPressureBar = -1;
|
||||||
this->params.tireRearLeftTempC = -1;
|
params.tireRearLeftTempC = -1;
|
||||||
this->params.tireRearLeftPressureBar = -1;
|
params.tireRearLeftPressureBar = -1;
|
||||||
this->params.tireRearRightTempC = -1;
|
params.tireRearRightTempC = -1;
|
||||||
this->params.tireRearRightPressureBar = -1;
|
params.tireRearRightPressureBar = -1;
|
||||||
for (int i = 0; i <= 10; i++) {
|
for (int i = 0; i <= 10; i++) {
|
||||||
this->params.soc10ced[i] = this->params.soc10cec[i] = this->params.soc10odo[i] = -1;
|
params.soc10ced[i] = params.soc10cec[i] = params.soc10odo[i] = -1;
|
||||||
this->params.soc10time[i] = 0;
|
params.soc10time[i] = 0;
|
||||||
}
|
}
|
||||||
for (int i = 0; i < 98; i++) {
|
for (int i = 0; i < 98; i++) {
|
||||||
this->params.cellVoltage[i] = 0;
|
params.cellVoltage[i] = 0;
|
||||||
}
|
}
|
||||||
this->params.cellCount = 0;
|
params.cellCount = 0;
|
||||||
for (int i = 0; i <= 100; i++) {
|
for (int i = 0; i <= 100; i++) {
|
||||||
this->params.chargingGraphMinKw[i] = -1;
|
params.chargingGraphMinKw[i] = -1;
|
||||||
this->params.chargingGraphMaxKw[i] = -1;
|
params.chargingGraphMaxKw[i] = -1;
|
||||||
this->params.chargingGraphBatMinTempC[i] = -100;
|
params.chargingGraphBatMinTempC[i] = -100;
|
||||||
this->params.chargingGraphBatMaxTempC[i] = -100;
|
params.chargingGraphBatMaxTempC[i] = -100;
|
||||||
this->params.chargingGraphHeaterTempC[i] = -100;
|
params.chargingGraphHeaterTempC[i] = -100;
|
||||||
this->params.chargingGraphWaterCoolantTempC[i] = -100;
|
params.chargingGraphWaterCoolantTempC[i] = -100;
|
||||||
}
|
}
|
||||||
|
//
|
||||||
|
tmpStr = "";
|
||||||
|
tmpStr.toCharArray(params.debugData, tmpStr.length() + 1);
|
||||||
|
tmpStr.toCharArray(params.debugData2, tmpStr.length() + 1);
|
||||||
|
|
||||||
// Menu
|
// Menu
|
||||||
this->menuItems = menuItemsSource;
|
menuItemsCount = sizeof(menuItemsSource) / sizeof(menuItemsSource[0]);
|
||||||
|
menuItems = menuItemsSource;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -130,25 +148,42 @@ float LiveData::hexToDec(String hexString, byte bytes, bool signedNum) {
|
|||||||
return (decValue > 32767 ? (float)decValue - 65536.0 : decValue);
|
return (decValue > 32767 ? (float)decValue - 65536.0 : decValue);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
Parsed from merged response row:
|
||||||
|
Hex to dec (1-2 byte values, signed/unsigned)
|
||||||
|
For 4 byte change int to long and add part for signed numbers
|
||||||
|
*/
|
||||||
|
|
||||||
|
float LiveData::hexToDecFromResponse(byte from, byte to, byte bytes, bool signedNum) {
|
||||||
|
return hexToDec(responseRowMerged.substring(from, to).c_str(), bytes, signedNum);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
Combination of responseRowMerged.substring -> strtol -> float
|
||||||
|
*/
|
||||||
|
float LiveData::decFromResponse(byte from, byte to, char **str_end, int base) {
|
||||||
|
return float(strtol(responseRowMerged.substring(from, to).c_str(), str_end, base));
|
||||||
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
Convert km to km or miles
|
Convert km to km or miles
|
||||||
*/
|
*/
|
||||||
float LiveData::km2distance(float inKm) {
|
float LiveData::km2distance(float inKm) {
|
||||||
return (this->settings.distanceUnit == 'k') ? inKm : inKm / 1.609344;
|
return (settings.distanceUnit == 'k') ? inKm : inKm / 1.609344;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
Convert celsius to celsius or farenheit
|
Convert celsius to celsius or farenheit
|
||||||
*/
|
*/
|
||||||
float LiveData::celsius2temperature(float inCelsius) {
|
float LiveData::celsius2temperature(float inCelsius) {
|
||||||
return (this->settings.temperatureUnit == 'c') ? inCelsius : (inCelsius * 1.8) + 32;
|
return (settings.temperatureUnit == 'c') ? inCelsius : (inCelsius * 1.8) + 32;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
Convert bar to bar or psi
|
Convert bar to bar or psi
|
||||||
*/
|
*/
|
||||||
float LiveData::bar2pressure(float inBar) {
|
float LiveData::bar2pressure(float inBar) {
|
||||||
return (this->settings.pressureUnit == 'b') ? inBar : inBar * 14.503773800722;
|
return (settings.pressureUnit == 'b') ? inBar : inBar * 14.503773800722;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
74
LiveData.h
74
LiveData.h
@@ -5,7 +5,7 @@
|
|||||||
#include <Arduino.h>
|
#include <Arduino.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include <WString.h>
|
#include <WString.h>
|
||||||
#include <String.h>
|
#include <string.h>
|
||||||
#include <sys/time.h>
|
#include <sys/time.h>
|
||||||
#include <BLEDevice.h>
|
#include <BLEDevice.h>
|
||||||
#include "config.h"
|
#include "config.h"
|
||||||
@@ -17,8 +17,13 @@
|
|||||||
#define CAR_KIA_ENIRO_2020_39 3
|
#define CAR_KIA_ENIRO_2020_39 3
|
||||||
#define CAR_HYUNDAI_KONA_2020_39 4
|
#define CAR_HYUNDAI_KONA_2020_39 4
|
||||||
#define CAR_RENAULT_ZOE 5
|
#define CAR_RENAULT_ZOE 5
|
||||||
|
#define CAR_KIA_NIRO_PHEV 6
|
||||||
#define CAR_DEBUG_OBD2_KIA 999
|
#define CAR_DEBUG_OBD2_KIA 999
|
||||||
|
|
||||||
|
//
|
||||||
|
#define COMM_TYPE_OBD2BLE4 0
|
||||||
|
#define COMM_TYPE_OBD2CAN 1
|
||||||
|
|
||||||
// SCREENS
|
// SCREENS
|
||||||
#define SCREEN_BLANK 0
|
#define SCREEN_BLANK 0
|
||||||
#define SCREEN_AUTO 1
|
#define SCREEN_AUTO 1
|
||||||
@@ -31,15 +36,28 @@
|
|||||||
|
|
||||||
// Structure with realtime values
|
// Structure with realtime values
|
||||||
typedef struct {
|
typedef struct {
|
||||||
|
// System
|
||||||
time_t currentTime;
|
time_t currentTime;
|
||||||
time_t chargingStartTime;
|
time_t chargingStartTime;
|
||||||
time_t automaticShutdownTimer;
|
time_t automaticShutdownTimer;
|
||||||
#ifdef SIM800L_ENABLED
|
// SIM
|
||||||
time_t lastDataSent;
|
time_t lastDataSent;
|
||||||
bool sim800l_enabled;
|
bool sim800l_enabled;
|
||||||
#endif //SIM800L_ENABLED
|
// GPS
|
||||||
|
bool currTimeSyncWithGps;
|
||||||
|
float gpsLat;
|
||||||
|
float gpsLon;
|
||||||
|
byte gpsSat; // satellites count
|
||||||
|
int16_t gpsAlt;
|
||||||
|
// SD card
|
||||||
|
bool sdcardInit;
|
||||||
|
bool sdcardRecording;
|
||||||
|
char sdcardFilename[32];
|
||||||
|
// Car params
|
||||||
bool ignitionOn;
|
bool ignitionOn;
|
||||||
bool ignitionOnPrevious;
|
bool ignitionOnPrevious;
|
||||||
|
uint64_t operationTimeSec;
|
||||||
|
bool sdcardCanNotify;
|
||||||
bool forwardDriveMode;
|
bool forwardDriveMode;
|
||||||
bool reverseDriveMode;
|
bool reverseDriveMode;
|
||||||
bool parkModeOrNeutral;
|
bool parkModeOrNeutral;
|
||||||
@@ -77,7 +95,7 @@ typedef struct {
|
|||||||
float batMinC;
|
float batMinC;
|
||||||
float batMaxC;
|
float batMaxC;
|
||||||
uint16_t batModuleTempCount;
|
uint16_t batModuleTempCount;
|
||||||
float batModuleTempC[12];
|
float batModuleTempC[25];
|
||||||
float coolingWaterTempC;
|
float coolingWaterTempC;
|
||||||
float coolantTemp1C;
|
float coolantTemp1C;
|
||||||
float coolantTemp2C;
|
float coolantTemp2C;
|
||||||
@@ -113,20 +131,23 @@ typedef struct {
|
|||||||
float soc10odo[11]; // odo history
|
float soc10odo[11]; // odo history
|
||||||
time_t soc10time[11]; // time for avg speed
|
time_t soc10time[11]; // time for avg speed
|
||||||
// additional
|
// additional
|
||||||
|
char debugData[256];
|
||||||
|
char debugData2[256];
|
||||||
/*
|
/*
|
||||||
uint8_t bmsIgnition;
|
|
||||||
uint8_t bmsMainRelay;
|
uint8_t bmsMainRelay;
|
||||||
uint8_t highVoltageCharging;
|
uint8_t highVoltageCharging;
|
||||||
float inverterCapacitorVoltage;
|
float inverterCapacitorVoltage;
|
||||||
float normalChargePort;
|
float normalChargePort;
|
||||||
float rapidChargePort;
|
float rapidChargePort;
|
||||||
float operationTimeHours;*/
|
;*/
|
||||||
} PARAMS_STRUC;
|
} PARAMS_STRUC;
|
||||||
|
|
||||||
// Setting stored to flash
|
// Setting stored to flash
|
||||||
typedef struct {
|
typedef struct {
|
||||||
byte initFlag; // 183 value
|
byte initFlag; // 183 value
|
||||||
byte settingsVersion; // current 3
|
byte settingsVersion; // current 5
|
||||||
|
// === settings version 1
|
||||||
|
// =================================
|
||||||
uint16_t carType; // 0 - Kia eNiro 2020, 1 - Hyundai Kona 2020, 2 - Hyudai Ioniq 2018
|
uint16_t carType; // 0 - Kia eNiro 2020, 1 - Hyundai Kona 2020, 2 - Hyudai Ioniq 2018
|
||||||
char obdMacAddress[20];
|
char obdMacAddress[20];
|
||||||
char serviceUUID[40];
|
char serviceUUID[40];
|
||||||
@@ -136,22 +157,45 @@ typedef struct {
|
|||||||
char distanceUnit; // k - kilometers
|
char distanceUnit; // k - kilometers
|
||||||
char temperatureUnit; // c - celsius
|
char temperatureUnit; // c - celsius
|
||||||
char pressureUnit; // b - bar
|
char pressureUnit; // b - bar
|
||||||
// version 2
|
// === settings version 3
|
||||||
|
// =================================
|
||||||
byte defaultScreen; // 1 .. 6
|
byte defaultScreen; // 1 .. 6
|
||||||
byte lcdBrightness; // 0 - auto, 1 .. 100%
|
byte lcdBrightness; // 0 - auto, 1 .. 100%
|
||||||
byte debugScreen; // 0 - off, 1 - on
|
byte debugScreen; // 0 - off, 1 - on
|
||||||
byte predrawnChargingGraphs; // 0 - off, 1 - on
|
byte predrawnChargingGraphs; // 0 - off, 1 - on
|
||||||
#ifdef SIM800L_ENABLED
|
// === settings version 4
|
||||||
|
// =================================
|
||||||
|
byte commType; // 0 - OBD2 BLE4 adapter, 1 - CAN
|
||||||
|
// Wifi
|
||||||
|
byte wifiEnabled; // 0/1
|
||||||
|
char wifiSsid[32];
|
||||||
|
char wifiPassword[32];
|
||||||
|
// NTP
|
||||||
|
byte ntpEnabled; // 0/1
|
||||||
|
byte ntpTimezone;
|
||||||
|
byte ntpDaySaveTime; // 0/1
|
||||||
|
// SDcard logging
|
||||||
|
byte sdcardEnabled; // 0/1
|
||||||
|
byte sdcardAutstartLog; // 0/1
|
||||||
|
// GPRS SIM800L
|
||||||
|
byte gprsEnabled; // 0/1
|
||||||
char gprsApn[64];
|
char gprsApn[64];
|
||||||
char remoteApiSrvr[64];
|
// Remote upload
|
||||||
char remoteApiKey[13];
|
byte remoteUploadEnabled; // 0/1
|
||||||
#endif //SIM800L_ENABLED
|
char remoteApiUrl[64];
|
||||||
|
char remoteApiKey[32];
|
||||||
|
//
|
||||||
|
byte headlightsReminder;
|
||||||
|
// === settings version 5
|
||||||
|
// =================================
|
||||||
|
byte gpsHwSerialPort; // 255-off, 0,1,2 - hw serial
|
||||||
|
//
|
||||||
} SETTINGS_STRUC;
|
} SETTINGS_STRUC;
|
||||||
|
|
||||||
|
|
||||||
//
|
//
|
||||||
class LiveData {
|
class LiveData {
|
||||||
private:
|
protected:
|
||||||
public:
|
public:
|
||||||
// Command loop
|
// Command loop
|
||||||
uint16_t commandQueueCount;
|
uint16_t commandQueueCount;
|
||||||
@@ -165,7 +209,7 @@ class LiveData {
|
|||||||
String currentAtshRequest = "";
|
String currentAtshRequest = "";
|
||||||
// Menu
|
// Menu
|
||||||
bool menuVisible = false;
|
bool menuVisible = false;
|
||||||
uint8_t menuItemsCount = 78;
|
uint8_t menuItemsCount;
|
||||||
uint16_t menuCurrent = 0;
|
uint16_t menuCurrent = 0;
|
||||||
uint8_t menuItemSelected = 0;
|
uint8_t menuItemSelected = 0;
|
||||||
uint8_t menuItemOffset = 0;
|
uint8_t menuItemOffset = 0;
|
||||||
@@ -190,6 +234,8 @@ class LiveData {
|
|||||||
//
|
//
|
||||||
void initParams();
|
void initParams();
|
||||||
float hexToDec(String hexString, byte bytes = 2, bool signedNum = true);
|
float hexToDec(String hexString, byte bytes = 2, bool signedNum = true);
|
||||||
|
float hexToDecFromResponse(byte from, byte to, byte bytes = 2, bool signedNum = true);
|
||||||
|
float decFromResponse(byte from, byte to, char **str_end = 0, int base = 16);
|
||||||
float km2distance(float inKm);
|
float km2distance(float inKm);
|
||||||
float celsius2temperature(float inCelsius);
|
float celsius2temperature(float inCelsius);
|
||||||
float bar2pressure(float inBar);
|
float bar2pressure(float inBar);
|
||||||
|
|||||||
@@ -4,7 +4,9 @@ Supported devices
|
|||||||
1. LILYGO TTGO T4 v1.3
|
1. LILYGO TTGO T4 v1.3
|
||||||
2. M5STACK CORE1 IOT Development Kit
|
2. M5STACK CORE1 IOT Development Kit
|
||||||
|
|
||||||
Working only with electric vehicles (Kia e-NIRO (EV), Hyundai Kona EV, Hyundai Ioniq EV). Vgate iCar Pro Bluetooth 4.0 (BLE4) OBD2 adapter is required. See Release notes, quick installation via flash tool bellow.
|
Working only with electric vehicles
|
||||||
|
Kia e-NIRO (EV), Hyundai Kona EV, Hyundai Ioniq EV, Kia Niro Phev 8.9kWh
|
||||||
|
Vgate iCar Pro Bluetooth 4.0 (BLE4) OBD2 adapter is required. See Release notes, quick installation via flash tool bellow.
|
||||||
|
|
||||||
Use it at your own risk!
|
Use it at your own risk!
|
||||||
Author: nick.n17@gmail.com (Lubos Petrovic / Slovakia)
|
Author: nick.n17@gmail.com (Lubos Petrovic / Slovakia)
|
||||||
|
|||||||
@@ -1,5 +1,31 @@
|
|||||||
# RELEASE NOTES
|
# RELEASE NOTES
|
||||||
|
|
||||||
|
### Next version
|
||||||
|
|
||||||
|
### v2.1.1 2020-12-14
|
||||||
|
- tech refactoring: `hexToDecFromResponse`, `decFromResponse`
|
||||||
|
- added support for GPS module on HW UART (user HWUART=2 for m5stack NEO-M8N)
|
||||||
|
- sd card logging - added gps sat/lat/lot/alt + SD filename + time is synchronized from GPS
|
||||||
|
- small improvements: menu cycling, shutdown timer
|
||||||
|
- added Kia Niro PHEV 8.9kWh support
|
||||||
|
|
||||||
|
### v2.1.0 2020-12-06
|
||||||
|
- m5stack mute speaker
|
||||||
|
- Settings v4 (wifi/gprs/sdcard/ntp/..)
|
||||||
|
- BLE skipped if mac is not set (00:00:00:00:00:00)
|
||||||
|
- Improved menu (L&R buttons hides menu, parent menu now keep position)
|
||||||
|
- SD card car params logging (json format)
|
||||||
|
(note: m5stack supports max 16GB FAT16/32 microSD)
|
||||||
|
- Supported serial console commands
|
||||||
|
serviceUUID=xxx
|
||||||
|
charTxUUID=xxx
|
||||||
|
charRxUUID=xxx
|
||||||
|
wifiSsid=xxx
|
||||||
|
wifiPassword=xxx
|
||||||
|
gprsApn=xxx
|
||||||
|
remoteApiUrl=xxx
|
||||||
|
remoteApiKey=xxx
|
||||||
|
|
||||||
### v2.0.0 2020-12-02
|
### v2.0.0 2020-12-02
|
||||||
- Project renamed from eNiroDashboard to evDash
|
- Project renamed from eNiroDashboard to evDash
|
||||||
|
|
||||||
|
|||||||
945
SIM800L.cpp
Normal file
945
SIM800L.cpp
Normal file
@@ -0,0 +1,945 @@
|
|||||||
|
/********************************************************************************
|
||||||
|
* Arduino-SIM800L-driver *
|
||||||
|
* ---------------------- *
|
||||||
|
* Arduino driver for GSM/GPRS module SIMCom SIM800L to make HTTP/S connections *
|
||||||
|
* with GET and POST methods *
|
||||||
|
* Author: Olivier Staquet *
|
||||||
|
* Last version available on https://github.com/ostaquet/Arduino-SIM800L-driver *
|
||||||
|
********************************************************************************
|
||||||
|
* MIT License
|
||||||
|
*
|
||||||
|
* Copyright (c) 2019 Olivier Staquet
|
||||||
|
*
|
||||||
|
* Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||||
|
* of this software and associated documentation files (the "Software"), to deal
|
||||||
|
* in the Software without restriction, including without limitation the rights
|
||||||
|
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||||
|
* copies of the Software, and to permit persons to whom the Software is
|
||||||
|
* furnished to do so, subject to the following conditions:
|
||||||
|
*
|
||||||
|
* The above copyright notice and this permission notice shall be included in all
|
||||||
|
* copies or substantial portions of the Software.
|
||||||
|
*
|
||||||
|
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||||
|
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||||
|
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||||
|
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||||
|
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||||
|
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
|
||||||
|
* SOFTWARE.
|
||||||
|
*******************************************************************************/
|
||||||
|
#include "SIM800L.h"
|
||||||
|
|
||||||
|
/**
|
||||||
|
* AT commands required (const char in PROGMEM to save memory usage)
|
||||||
|
*/
|
||||||
|
const char AT_CMD_BASE[] PROGMEM = "AT"; // Basic AT command to check the link
|
||||||
|
|
||||||
|
const char AT_CMD_CSQ[] PROGMEM = "AT+CSQ"; // Check the signal strengh
|
||||||
|
const char AT_CMD_ATI[] PROGMEM = "ATI"; // Output version of the module
|
||||||
|
const char AT_CMD_GMR[] PROGMEM = "AT+GMR"; // Output version of the firmware
|
||||||
|
const char AT_CMD_SIM_CARD[] PROGMEM = "AT+CCID"; // Get Sim Card version
|
||||||
|
|
||||||
|
const char AT_CMD_CFUN_TEST[] PROGMEM = "AT+CFUN?"; // Check the current power mode
|
||||||
|
const char AT_CMD_CFUN0[] PROGMEM = "AT+CFUN=0"; // Switch minimum power mode
|
||||||
|
const char AT_CMD_CFUN1[] PROGMEM = "AT+CFUN=1"; // Switch normal power mode
|
||||||
|
const char AT_CMD_CFUN4[] PROGMEM = "AT+CFUN=4"; // Switch sleep power mode
|
||||||
|
|
||||||
|
const char AT_CMD_CREG_TEST[] PROGMEM = "AT+CREG?"; // Check the network registration status
|
||||||
|
const char AT_CMD_SAPBR_GPRS[] PROGMEM = "AT+SAPBR=3,1,\"Contype\",\"GPRS\""; // Configure the GPRS bearer
|
||||||
|
const char AT_CMD_SAPBR_APN[] PROGMEM = "AT+SAPBR=3,1,\"APN\","; // Configure the APN for the GPRS
|
||||||
|
const char AT_CMD_SAPBR1[] PROGMEM = "AT+SAPBR=1,1"; // Connect GPRS
|
||||||
|
const char AT_CMD_SAPBR2[] PROGMEM = "AT+SAPBR=2,1";
|
||||||
|
const char AT_CMD_SAPBR0[] PROGMEM = "AT+SAPBR=0,1"; // Disconnect GPRS
|
||||||
|
|
||||||
|
const char AT_CMD_HTTPINIT[] PROGMEM = "AT+HTTPINIT"; // Init HTTP connection
|
||||||
|
const char AT_CMD_HTTPPARA_CID[] PROGMEM = "AT+HTTPPARA=\"CID\",1"; // Connect HTTP through GPRS bearer
|
||||||
|
const char AT_CMD_HTTPPARA_URL[] PROGMEM = "AT+HTTPPARA=\"URL\","; // Define the URL to connect in HTTP
|
||||||
|
const char AT_CMD_HTTPPARA_USERDATA[] PROGMEM = "AT+HTTPPARA=\"USERDATA\","; // Define the header(s)
|
||||||
|
const char AT_CMD_HTTPPARA_CONTENT[] PROGMEM = "AT+HTTPPARA=\"CONTENT\","; // Define the content type for the HTTP POST
|
||||||
|
const char AT_CMD_HTTPSSL_Y[] PROGMEM = "AT+HTTPSSL=1"; // Enable SSL for HTTP connection
|
||||||
|
const char AT_CMD_HTTPSSL_N[] PROGMEM = "AT+HTTPSSL=0"; // Disable SSL for HTTP connection
|
||||||
|
const char AT_CMD_HTTPACTION0[] PROGMEM = "AT+HTTPACTION=0"; // Launch HTTP GET action
|
||||||
|
const char AT_CMD_HTTPACTION1[] PROGMEM = "AT+HTTPACTION=1"; // Launch HTTP POST action
|
||||||
|
const char AT_CMD_HTTPREAD[] PROGMEM = "AT+HTTPREAD"; // Start reading HTTP return data
|
||||||
|
const char AT_CMD_HTTPTERM[] PROGMEM = "AT+HTTPTERM"; // Terminate HTTP connection
|
||||||
|
|
||||||
|
const char AT_RSP_OK[] PROGMEM = "OK"; // Expected answer OK
|
||||||
|
const char AT_RSP_DOWNLOAD[] PROGMEM = "DOWNLOAD"; // Expected answer DOWNLOAD
|
||||||
|
const char AT_RSP_HTTPREAD[] PROGMEM = "+HTTPREAD: "; // Expected answer HTTPREAD
|
||||||
|
const char AT_RSP_SAPBR[] PROGMEM = "+SAPBR: 1,1,"; // Expected answer SAPBR:1,1
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Constructor; Init the driver, communication with the module and shared
|
||||||
|
* buffer used by the driver (to avoid multiples allocation)
|
||||||
|
*/
|
||||||
|
SIM800L::SIM800L(Stream* _stream, uint8_t _pinRst, uint16_t _internalBufferSize, uint16_t _recvBufferSize, Stream* _debugStream) {
|
||||||
|
// Store local variables
|
||||||
|
stream = _stream;
|
||||||
|
enableDebug = _debugStream != NULL;
|
||||||
|
debugStream = _debugStream;
|
||||||
|
pinReset = _pinRst;
|
||||||
|
|
||||||
|
if(pinReset != RESET_PIN_NOT_USED) {
|
||||||
|
// Setup the reset pin and force a reset of the module
|
||||||
|
pinMode(pinReset, OUTPUT);
|
||||||
|
reset();
|
||||||
|
}
|
||||||
|
|
||||||
|
// Prepare internal buffers
|
||||||
|
if(enableDebug) {
|
||||||
|
debugStream->print(F("SIM800L : Prepare internal buffer of "));
|
||||||
|
debugStream->print(_internalBufferSize);
|
||||||
|
debugStream->println(F(" bytes"));
|
||||||
|
}
|
||||||
|
internalBufferSize = _internalBufferSize;
|
||||||
|
internalBuffer = (char*) malloc(internalBufferSize);
|
||||||
|
|
||||||
|
if(enableDebug) {
|
||||||
|
debugStream->print(F("SIM800L : Prepare reception buffer of "));
|
||||||
|
debugStream->print(_recvBufferSize);
|
||||||
|
debugStream->println(F(" bytes"));
|
||||||
|
}
|
||||||
|
recvBufferSize = _recvBufferSize;
|
||||||
|
recvBuffer = (char *) malloc(recvBufferSize);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Destructor; cleanup the memory allocated by the driver
|
||||||
|
*/
|
||||||
|
SIM800L::~SIM800L() {
|
||||||
|
free(internalBuffer);
|
||||||
|
free(recvBuffer);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Do HTTP/S POST to a specific URL
|
||||||
|
*/
|
||||||
|
uint16_t SIM800L::doPost(const char* url, const char* contentType, const char* payload, uint16_t clientWriteTimeoutMs, uint16_t serverReadTimeoutMs) {
|
||||||
|
return doPost(url, NULL, contentType, payload, clientWriteTimeoutMs , serverReadTimeoutMs);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Do HTTP/S POST to a specific URL with headers
|
||||||
|
*/
|
||||||
|
uint16_t SIM800L::doPost(const char* url, const char* headers, const char* contentType, const char* payload, uint16_t clientWriteTimeoutMs, uint16_t serverReadTimeoutMs) {
|
||||||
|
// Cleanup the receive buffer
|
||||||
|
initRecvBuffer();
|
||||||
|
dataSize = 0;
|
||||||
|
|
||||||
|
// Initiate HTTP/S session with the module
|
||||||
|
uint16_t initRC = initiateHTTP(url, headers);
|
||||||
|
if(initRC > 0) {
|
||||||
|
return initRC;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Define the content type
|
||||||
|
sendCommand_P(AT_CMD_HTTPPARA_CONTENT, contentType);
|
||||||
|
if(!readResponseCheckAnswer_P(DEFAULT_TIMEOUT, AT_RSP_OK)) {
|
||||||
|
if(enableDebug) debugStream->println(F("SIM800L : doPost() - Unable to define the content type"));
|
||||||
|
return 702;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Prepare to send the payload
|
||||||
|
char* tmpBuf = (char*)malloc(30);
|
||||||
|
sprintf(tmpBuf, "AT+HTTPDATA=%d,%d", strlen(payload), clientWriteTimeoutMs);
|
||||||
|
sendCommand(tmpBuf);
|
||||||
|
free(tmpBuf);
|
||||||
|
if(!readResponseCheckAnswer_P(DEFAULT_TIMEOUT, AT_RSP_DOWNLOAD)) {
|
||||||
|
if(enableDebug) debugStream->println(F("SIM800L : doPost() - Unable to send payload to module"));
|
||||||
|
return 707;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Write the payload on the module
|
||||||
|
if(enableDebug) {
|
||||||
|
debugStream->print(F("SIM800L : doPost() - Payload to send : "));
|
||||||
|
debugStream->println(payload);
|
||||||
|
}
|
||||||
|
|
||||||
|
purgeSerial();
|
||||||
|
stream->write(payload);
|
||||||
|
stream->flush();
|
||||||
|
delay(500);
|
||||||
|
|
||||||
|
// Start HTTP POST action
|
||||||
|
sendCommand_P(AT_CMD_HTTPACTION1);
|
||||||
|
if(!readResponseCheckAnswer_P(DEFAULT_TIMEOUT, AT_RSP_OK)) {
|
||||||
|
if(enableDebug) debugStream->println(F("SIM800L : doPost() - Unable to initiate POST action"));
|
||||||
|
return 703;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Wait answer from the server
|
||||||
|
if(!readResponse(serverReadTimeoutMs)) {
|
||||||
|
if(enableDebug) debugStream->println(F("SIM800L : doPost() - Server timeout"));
|
||||||
|
return 408;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Extract status information
|
||||||
|
int16_t idxBase = strIndex(internalBuffer, "+HTTPACTION: 1,");
|
||||||
|
if(idxBase < 0) {
|
||||||
|
if(enableDebug) debugStream->println(F("SIM800L : doPost() - Invalid answer on HTTP POST"));
|
||||||
|
return 703;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Get the HTTP return code
|
||||||
|
uint16_t httpRC = 0;
|
||||||
|
httpRC += (internalBuffer[idxBase + 15] - '0') * 100;
|
||||||
|
httpRC += (internalBuffer[idxBase + 16] - '0') * 10;
|
||||||
|
httpRC += (internalBuffer[idxBase + 17] - '0') * 1;
|
||||||
|
|
||||||
|
if(enableDebug) {
|
||||||
|
debugStream->print(F("SIM800L : doPost() - HTTP status "));
|
||||||
|
debugStream->println(httpRC);
|
||||||
|
}
|
||||||
|
|
||||||
|
if(httpRC == 200) {
|
||||||
|
// Get the size of the data to receive
|
||||||
|
dataSize = 0;
|
||||||
|
for(uint16_t i = 0; (internalBuffer[idxBase + 19 + i] - '0') >= 0 && (internalBuffer[idxBase + 19 + i] - '0') <= 9; i++) {
|
||||||
|
if(i != 0) {
|
||||||
|
dataSize = dataSize * 10;
|
||||||
|
}
|
||||||
|
dataSize += (internalBuffer[idxBase + 19 + i] - '0');
|
||||||
|
}
|
||||||
|
|
||||||
|
if(enableDebug) {
|
||||||
|
debugStream->print(F("SIM800L : doPost() - Data size received of "));
|
||||||
|
debugStream->print(dataSize);
|
||||||
|
debugStream->println(F(" bytes"));
|
||||||
|
}
|
||||||
|
|
||||||
|
// Ask for reading and detect the start of the reading...
|
||||||
|
sendCommand_P(AT_CMD_HTTPREAD);
|
||||||
|
if(!readResponseCheckAnswer_P(DEFAULT_TIMEOUT, AT_RSP_HTTPREAD, 2)) {
|
||||||
|
return 705;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Read number of bytes defined in the dataSize
|
||||||
|
for(uint16_t i = 0; i < dataSize && i < recvBufferSize; i++) {
|
||||||
|
while(!stream->available());
|
||||||
|
if(stream->available()) {
|
||||||
|
// Load the next char
|
||||||
|
recvBuffer[i] = stream->read();
|
||||||
|
// If the character is CR or LF, ignore it (it's probably part of the module communication schema)
|
||||||
|
if((recvBuffer[i] == '\r') || (recvBuffer[i] == '\n')) {
|
||||||
|
i--;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if(recvBufferSize < dataSize) {
|
||||||
|
dataSize = recvBufferSize;
|
||||||
|
if(enableDebug) {
|
||||||
|
debugStream->println(F("SIM800L : doPost() - Buffer overflow while loading data from HTTP. Keep only first bytes..."));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// We are expecting a final OK
|
||||||
|
if(!readResponseCheckAnswer_P(DEFAULT_TIMEOUT, AT_RSP_OK)) {
|
||||||
|
if(enableDebug) debugStream->println(F("SIM800L : doPost() - Invalid end of data while reading HTTP result from the module"));
|
||||||
|
return 705;
|
||||||
|
}
|
||||||
|
|
||||||
|
if(enableDebug) {
|
||||||
|
debugStream->print(F("SIM800L : doPost() - Received from HTTP POST : "));
|
||||||
|
debugStream->println(recvBuffer);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Terminate HTTP/S session
|
||||||
|
uint16_t termRC = terminateHTTP();
|
||||||
|
if(termRC > 0) {
|
||||||
|
return termRC;
|
||||||
|
}
|
||||||
|
|
||||||
|
return httpRC;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Do HTTP/S GET on a specific URL
|
||||||
|
*/
|
||||||
|
uint16_t SIM800L::doGet(const char* url, uint16_t serverReadTimeoutMs) {
|
||||||
|
return doGet(url, NULL, serverReadTimeoutMs);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Do HTTP/S GET on a specific URL with headers
|
||||||
|
*/
|
||||||
|
uint16_t SIM800L::doGet(const char* url, const char* headers, uint16_t serverReadTimeoutMs) {
|
||||||
|
// Cleanup the receive buffer
|
||||||
|
initRecvBuffer();
|
||||||
|
dataSize = 0;
|
||||||
|
|
||||||
|
// Initiate HTTP/S session
|
||||||
|
uint16_t initRC = initiateHTTP(url, headers);
|
||||||
|
if(initRC > 0) {
|
||||||
|
return initRC;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Start HTTP GET action
|
||||||
|
sendCommand_P(AT_CMD_HTTPACTION0);
|
||||||
|
if(!readResponseCheckAnswer_P(DEFAULT_TIMEOUT, AT_RSP_OK)) {
|
||||||
|
if(enableDebug) debugStream->println(F("SIM800L : doGet() - Unable to initiate GET action"));
|
||||||
|
return 703;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Wait answer from the server
|
||||||
|
if(!readResponse(serverReadTimeoutMs)) {
|
||||||
|
if(enableDebug) debugStream->println(F("SIM800L : doGet() - Server timeout"));
|
||||||
|
return 408;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Extract status information
|
||||||
|
int16_t idxBase = strIndex(internalBuffer, "+HTTPACTION: 0,");
|
||||||
|
if(idxBase < 0) {
|
||||||
|
if(enableDebug) debugStream->println(F("SIM800L : doGet() - Invalid answer on HTTP GET"));
|
||||||
|
return 703;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Get the HTTP return code
|
||||||
|
uint16_t httpRC = 0;
|
||||||
|
httpRC += (internalBuffer[idxBase + 15] - '0') * 100;
|
||||||
|
httpRC += (internalBuffer[idxBase + 16] - '0') * 10;
|
||||||
|
httpRC += (internalBuffer[idxBase + 17] - '0') * 1;
|
||||||
|
|
||||||
|
if(enableDebug) {
|
||||||
|
debugStream->print(F("SIM800L : doGet() - HTTP status "));
|
||||||
|
debugStream->println(httpRC);
|
||||||
|
}
|
||||||
|
|
||||||
|
if(httpRC == 200) {
|
||||||
|
// Get the size of the data to receive
|
||||||
|
dataSize = 0;
|
||||||
|
for(uint16_t i = 0; (internalBuffer[idxBase + 19 + i] - '0') >= 0 && (internalBuffer[idxBase + 19 + i] - '0') <= 9; i++) {
|
||||||
|
if(i != 0) {
|
||||||
|
dataSize = dataSize * 10;
|
||||||
|
}
|
||||||
|
dataSize += (internalBuffer[idxBase + 19 + i] - '0');
|
||||||
|
}
|
||||||
|
|
||||||
|
if(enableDebug) {
|
||||||
|
debugStream->print(F("SIM800L : doGet() - Data size received of "));
|
||||||
|
debugStream->print(dataSize);
|
||||||
|
debugStream->println(F(" bytes"));
|
||||||
|
}
|
||||||
|
|
||||||
|
// Ask for reading and detect the start of the reading...
|
||||||
|
sendCommand_P(AT_CMD_HTTPREAD);
|
||||||
|
if(!readResponseCheckAnswer_P(DEFAULT_TIMEOUT, AT_RSP_HTTPREAD, 2)) {
|
||||||
|
return 705;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Read number of bytes defined in the dataSize
|
||||||
|
for(uint16_t i = 0; i < dataSize && i < recvBufferSize; i++) {
|
||||||
|
while(!stream->available());
|
||||||
|
if(stream->available()) {
|
||||||
|
// Load the next char
|
||||||
|
recvBuffer[i] = stream->read();
|
||||||
|
// If the character is CR or LF, ignore it (it's probably part of the module communication schema)
|
||||||
|
if((recvBuffer[i] == '\r') || (recvBuffer[i] == '\n')) {
|
||||||
|
i--;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if(recvBufferSize < dataSize) {
|
||||||
|
dataSize = recvBufferSize;
|
||||||
|
if(enableDebug) {
|
||||||
|
debugStream->println(F("SIM800L : doGet() - Buffer overflow while loading data from HTTP. Keep only first bytes..."));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// We are expecting a final OK
|
||||||
|
if(!readResponseCheckAnswer_P(DEFAULT_TIMEOUT, AT_RSP_OK)) {
|
||||||
|
if(enableDebug) debugStream->println(F("SIM800L : doGet() - Invalid end of data while reading HTTP result from the module"));
|
||||||
|
return 705;
|
||||||
|
}
|
||||||
|
|
||||||
|
if(enableDebug) {
|
||||||
|
debugStream->print(F("SIM800L : doGet() - Received from HTTP GET : "));
|
||||||
|
debugStream->println(recvBuffer);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Terminate HTTP/S session
|
||||||
|
uint16_t termRC = terminateHTTP();
|
||||||
|
if(termRC > 0) {
|
||||||
|
return termRC;
|
||||||
|
}
|
||||||
|
|
||||||
|
return httpRC;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Meta method to initiate the HTTP/S session on the module
|
||||||
|
*/
|
||||||
|
uint16_t SIM800L::initiateHTTP(const char* url, const char* headers) {
|
||||||
|
// Init HTTP connection
|
||||||
|
sendCommand_P(AT_CMD_HTTPINIT);
|
||||||
|
if(!readResponseCheckAnswer_P(DEFAULT_TIMEOUT, AT_RSP_OK)) {
|
||||||
|
if(enableDebug) debugStream->println(F("SIM800L : initiateHTTP() - Unable to init HTTP"));
|
||||||
|
return 701;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Use the GPRS bearer
|
||||||
|
sendCommand_P(AT_CMD_HTTPPARA_CID);
|
||||||
|
if(!readResponseCheckAnswer_P(DEFAULT_TIMEOUT, AT_RSP_OK)) {
|
||||||
|
if(enableDebug) debugStream->println(F("SIM800L : initiateHTTP() - Unable to define bearer"));
|
||||||
|
return 702;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Define URL to look for
|
||||||
|
sendCommand_P(AT_CMD_HTTPPARA_URL, url);
|
||||||
|
if(!readResponseCheckAnswer_P(DEFAULT_TIMEOUT, AT_RSP_OK)) {
|
||||||
|
if(enableDebug) debugStream->println(F("SIM800L : initiateHTTP() - Unable to define the URL"));
|
||||||
|
return 702;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Set Headers
|
||||||
|
if (headers != NULL) {
|
||||||
|
sendCommand_P(AT_CMD_HTTPPARA_USERDATA, headers);
|
||||||
|
if(!readResponseCheckAnswer_P(DEFAULT_TIMEOUT, AT_RSP_OK)) {
|
||||||
|
if(enableDebug) debugStream->println(F("SIM800L : initiateHTTP() - Unable to define Headers"));
|
||||||
|
return 702;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Check if the firmware support HTTPSSL command
|
||||||
|
bool isSupportSSL = false;
|
||||||
|
char* version = getVersion();
|
||||||
|
int16_t rIdx = strIndex(version, "R");
|
||||||
|
if(rIdx > 0) {
|
||||||
|
uint8_t releaseInt = (version[rIdx + 1] - '0') * 10 + (version[rIdx + 2] - '0');
|
||||||
|
|
||||||
|
// The release should be greater or equals to 14 to support SSL stack
|
||||||
|
if(releaseInt >= 14) {
|
||||||
|
isSupportSSL = true;
|
||||||
|
if(enableDebug) debugStream->println(F("SIM800L : initiateHTTP() - Support of SSL enabled"));
|
||||||
|
} else {
|
||||||
|
isSupportSSL = false;
|
||||||
|
if(enableDebug) debugStream->println(F("SIM800L : initiateHTTP() - Support of SSL disabled (SIM800L firware below R14)"));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Send HTTPSSL command only if the version is greater or equals to 14
|
||||||
|
if(isSupportSSL) {
|
||||||
|
// HTTP or HTTPS
|
||||||
|
if(strIndex(url, "https://") == 0) {
|
||||||
|
sendCommand_P(AT_CMD_HTTPSSL_Y);
|
||||||
|
if(!readResponseCheckAnswer_P(DEFAULT_TIMEOUT, AT_RSP_OK)) {
|
||||||
|
if(enableDebug) debugStream->println(F("SIM800L : initiateHTTP() - Unable to switch to HTTPS"));
|
||||||
|
return 702;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
sendCommand_P(AT_CMD_HTTPSSL_N);
|
||||||
|
if(!readResponseCheckAnswer_P(DEFAULT_TIMEOUT, AT_RSP_OK)) {
|
||||||
|
if(enableDebug) debugStream->println(F("SIM800L : initiateHTTP() - Unable to switch to HTTP"));
|
||||||
|
return 702;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Meta method to terminate the HTTP/S session on the module
|
||||||
|
*/
|
||||||
|
uint16_t SIM800L::terminateHTTP() {
|
||||||
|
// Close HTTP connection
|
||||||
|
sendCommand_P(AT_CMD_HTTPTERM);
|
||||||
|
if(!readResponseCheckAnswer_P(DEFAULT_TIMEOUT, AT_RSP_OK)) {
|
||||||
|
if(enableDebug) debugStream->println(F("SIM800L : terminateHTTP() - Unable to close HTTP session"));
|
||||||
|
return 706;
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Force a reset of the module
|
||||||
|
*/
|
||||||
|
void SIM800L::reset() {
|
||||||
|
if(pinReset != RESET_PIN_NOT_USED)
|
||||||
|
{
|
||||||
|
// Some logging
|
||||||
|
if(enableDebug) debugStream->println(F("SIM800L : Reset"));
|
||||||
|
|
||||||
|
// Reset the device
|
||||||
|
digitalWrite(pinReset, HIGH);
|
||||||
|
delay(500);
|
||||||
|
digitalWrite(pinReset, LOW);
|
||||||
|
delay(500);
|
||||||
|
digitalWrite(pinReset, HIGH);
|
||||||
|
delay(1000);
|
||||||
|
} else {
|
||||||
|
// Some logging
|
||||||
|
if(enableDebug) debugStream->println(F("SIM800L : Reset requested but reset pin undefined"));
|
||||||
|
if(enableDebug) debugStream->println(F("SIM800L : No reset"));
|
||||||
|
}
|
||||||
|
|
||||||
|
// Purge the serial
|
||||||
|
stream->flush();
|
||||||
|
while (stream->available()) {
|
||||||
|
stream->read();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Return the size of data received after the last successful HTTP connection
|
||||||
|
*/
|
||||||
|
uint16_t SIM800L::getDataSizeReceived() {
|
||||||
|
return dataSize;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Return the buffer of data received after the last successful HTTP connection
|
||||||
|
*/
|
||||||
|
char* SIM800L::getDataReceived() {
|
||||||
|
return recvBuffer;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Status function: Check if AT command works
|
||||||
|
*/
|
||||||
|
bool SIM800L::isReady() {
|
||||||
|
sendCommand_P(AT_CMD_BASE);
|
||||||
|
return readResponseCheckAnswer_P(DEFAULT_TIMEOUT, AT_RSP_OK);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Status function: Check the power mode
|
||||||
|
*/
|
||||||
|
PowerMode SIM800L::getPowerMode() {
|
||||||
|
sendCommand_P(AT_CMD_CFUN_TEST);
|
||||||
|
if(readResponse(DEFAULT_TIMEOUT)) {
|
||||||
|
// Check if there is an error
|
||||||
|
int16_t errIdx = strIndex(internalBuffer, "ERROR");
|
||||||
|
if(errIdx > 0) {
|
||||||
|
return POW_ERROR;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Extract the value
|
||||||
|
int16_t idx = strIndex(internalBuffer, "+CFUN: ");
|
||||||
|
char value = internalBuffer[idx + 7];
|
||||||
|
|
||||||
|
// Prepare the clear output
|
||||||
|
switch(value) {
|
||||||
|
case '0' : return MINIMUM;
|
||||||
|
case '1' : return NORMAL;
|
||||||
|
case '4' : return SLEEP;
|
||||||
|
default : return POW_UNKNOWN;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return POW_ERROR;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Status function: Get version of the module
|
||||||
|
*/
|
||||||
|
char* SIM800L::getVersion() {
|
||||||
|
sendCommand_P(AT_CMD_ATI);
|
||||||
|
if(readResponse(DEFAULT_TIMEOUT)) {
|
||||||
|
// Extract the value
|
||||||
|
int16_t idx = strIndex(internalBuffer, "SIM");
|
||||||
|
int16_t idxEnd = strIndex(internalBuffer, "\r", idx+1);
|
||||||
|
|
||||||
|
// Store it on the recv buffer (not used at the moment)
|
||||||
|
initRecvBuffer();
|
||||||
|
for(uint16_t i = 0; i < idxEnd - idx; i++) {
|
||||||
|
recvBuffer[i] = internalBuffer[idx + i];
|
||||||
|
}
|
||||||
|
return getDataReceived();
|
||||||
|
} else {
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Status function: Get firmware version
|
||||||
|
*/
|
||||||
|
char* SIM800L::getFirmware() {
|
||||||
|
sendCommand_P(AT_CMD_GMR);
|
||||||
|
if(readResponse(DEFAULT_TIMEOUT)) {
|
||||||
|
// Extract the value
|
||||||
|
int16_t idx = strIndex(internalBuffer, "AT+GMR") + 9;
|
||||||
|
int16_t idxEnd = strIndex(internalBuffer, "\r", idx+1);
|
||||||
|
|
||||||
|
// Store it on the recv buffer (not used at the moment)
|
||||||
|
initRecvBuffer();
|
||||||
|
for(uint16_t i = 0; i < idxEnd - idx; i++) {
|
||||||
|
recvBuffer[i] = internalBuffer[idx + i];
|
||||||
|
}
|
||||||
|
return getDataReceived();
|
||||||
|
} else {
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Status function: Requests the simcard number
|
||||||
|
*/
|
||||||
|
char* SIM800L::getSimCardNumber() {
|
||||||
|
sendCommand_P(AT_CMD_SIM_CARD);
|
||||||
|
if(readResponse(DEFAULT_TIMEOUT)) {
|
||||||
|
int16_t idx = strIndex(internalBuffer, "AT+CCID") + 10;
|
||||||
|
int16_t idxEnd = strIndex(internalBuffer, "\r", idx+1);
|
||||||
|
|
||||||
|
// Store it on the recv buffer (not used at the moment)
|
||||||
|
initRecvBuffer();
|
||||||
|
for(uint16_t i = 0; i < idxEnd - idx; i++) {
|
||||||
|
recvBuffer[i] = internalBuffer[idx + i];
|
||||||
|
}
|
||||||
|
return getDataReceived();
|
||||||
|
} else {
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Status function: Check if the module is registered on the network
|
||||||
|
*/
|
||||||
|
NetworkRegistration SIM800L::getRegistrationStatus() {
|
||||||
|
sendCommand_P(AT_CMD_CREG_TEST);
|
||||||
|
if(readResponse(DEFAULT_TIMEOUT)) {
|
||||||
|
// Check if there is an error
|
||||||
|
int16_t errIdx = strIndex(internalBuffer, "ERROR");
|
||||||
|
if(errIdx > 0) {
|
||||||
|
return NET_ERROR;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Extract the value
|
||||||
|
int16_t idx = strIndex(internalBuffer, "+CREG: ");
|
||||||
|
char value = internalBuffer[idx + 9];
|
||||||
|
|
||||||
|
// Prepare the clear output
|
||||||
|
switch(value) {
|
||||||
|
case '0' : return NOT_REGISTERED;
|
||||||
|
case '1' : return REGISTERED_HOME;
|
||||||
|
case '2' : return SEARCHING;
|
||||||
|
case '3' : return DENIED;
|
||||||
|
case '5' : return REGISTERED_ROAMING;
|
||||||
|
default : return NET_UNKNOWN;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return NET_ERROR;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Setup the GPRS connectivity
|
||||||
|
* As input, give the APN string of the operator
|
||||||
|
*/
|
||||||
|
bool SIM800L::setupGPRS(const char* apn) {
|
||||||
|
// Prepare the GPRS connection as the bearer
|
||||||
|
sendCommand_P(AT_CMD_SAPBR_GPRS);
|
||||||
|
if(!readResponseCheckAnswer_P(20000, AT_RSP_OK)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Set the config of the bearer with the APN
|
||||||
|
sendCommand_P(AT_CMD_SAPBR_APN, apn);
|
||||||
|
return readResponseCheckAnswer_P(20000, AT_RSP_OK);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Open the GPRS connectivity
|
||||||
|
*/
|
||||||
|
bool SIM800L::connectGPRS() {
|
||||||
|
sendCommand_P(AT_CMD_SAPBR1);
|
||||||
|
// Timout is max 85 seconds according to SIM800 specifications
|
||||||
|
// We will wait for 65s to be within uint16_t
|
||||||
|
return readResponseCheckAnswer_P(65000, AT_RSP_OK);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Check if GPRS is connected
|
||||||
|
*/
|
||||||
|
bool SIM800L::isConnectedGPRS() {
|
||||||
|
sendCommand_P(AT_CMD_SAPBR2);
|
||||||
|
return readResponseCheckAnswer_P(65000, AT_RSP_SAPBR);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Close the GPRS connectivity
|
||||||
|
*/
|
||||||
|
bool SIM800L::disconnectGPRS() {
|
||||||
|
sendCommand_P(AT_CMD_SAPBR0);
|
||||||
|
// Timout is max 65 seconds according to SIM800 specifications
|
||||||
|
return readResponseCheckAnswer_P(65000, AT_RSP_OK);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Define the power mode
|
||||||
|
* Available : MINIMUM, NORMAL, SLEEP
|
||||||
|
* Return true is the mode is correctly switched
|
||||||
|
*/
|
||||||
|
bool SIM800L::setPowerMode(PowerMode powerMode) {
|
||||||
|
// Check if the power mode requested is not ERROR or UNKNOWN
|
||||||
|
if(powerMode == POW_ERROR || powerMode == POW_UNKNOWN) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Check the current power mode
|
||||||
|
PowerMode currentPowerMode = getPowerMode();
|
||||||
|
|
||||||
|
// If the current power mode is undefined, abord
|
||||||
|
if(currentPowerMode == POW_ERROR || currentPowerMode == POW_UNKNOWN) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
// If the current power mode is the same that the requested power mode, say it's OK
|
||||||
|
if(currentPowerMode == powerMode) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
// If SLEEP or MINIMUM, only NORMAL is allowed
|
||||||
|
if((currentPowerMode == SLEEP || currentPowerMode == MINIMUM) && (powerMode != NORMAL)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Send the command
|
||||||
|
char value;
|
||||||
|
switch(powerMode) {
|
||||||
|
case MINIMUM :
|
||||||
|
sendCommand_P(AT_CMD_CFUN0);
|
||||||
|
break;
|
||||||
|
case SLEEP :
|
||||||
|
sendCommand_P(AT_CMD_CFUN4);
|
||||||
|
break;
|
||||||
|
case NORMAL :
|
||||||
|
default :
|
||||||
|
sendCommand_P(AT_CMD_CFUN1);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Read but don't care about the result
|
||||||
|
purgeSerial();
|
||||||
|
|
||||||
|
// Check the current power mode
|
||||||
|
currentPowerMode = getPowerMode();
|
||||||
|
|
||||||
|
// If the current power mode is the same that the requested power mode, say it's OK
|
||||||
|
return currentPowerMode == powerMode;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Status function: Check the strengh of the signal
|
||||||
|
*/
|
||||||
|
uint8_t SIM800L::getSignal() {
|
||||||
|
sendCommand_P(AT_CMD_CSQ);
|
||||||
|
if(readResponse(DEFAULT_TIMEOUT)) {
|
||||||
|
int16_t idxBase = strIndex(internalBuffer, "AT+CSQ");
|
||||||
|
if(idxBase != 0) {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
int16_t idxEnd = strIndex(internalBuffer, ",", idxBase);
|
||||||
|
uint8_t value = internalBuffer[idxEnd - 1] - '0';
|
||||||
|
if(internalBuffer[idxEnd - 2] != ' ') {
|
||||||
|
value += (internalBuffer[idxEnd - 2] - '0') * 10;
|
||||||
|
}
|
||||||
|
if(value > 31) {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
return value;
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
/*****************************************************************************************
|
||||||
|
* HELPERS
|
||||||
|
*****************************************************************************************/
|
||||||
|
/**
|
||||||
|
* Find string "findStr" in another string "str"
|
||||||
|
* Returns true if found, false elsewhere
|
||||||
|
*/
|
||||||
|
int16_t SIM800L::strIndex(const char* str, const char* findStr, uint16_t startIdx) {
|
||||||
|
int16_t firstIndex = -1;
|
||||||
|
int16_t sizeMatch = 0;
|
||||||
|
for(int16_t i = startIdx; i < strlen(str); i++) {
|
||||||
|
if(sizeMatch >= strlen(findStr)) {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
if(str[i] == findStr[sizeMatch]) {
|
||||||
|
if(firstIndex < 0) {
|
||||||
|
firstIndex = i;
|
||||||
|
}
|
||||||
|
sizeMatch++;
|
||||||
|
} else {
|
||||||
|
firstIndex = -1;
|
||||||
|
sizeMatch = 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if(sizeMatch >= strlen(findStr)) {
|
||||||
|
return firstIndex;
|
||||||
|
} else {
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Init internal buffer
|
||||||
|
*/
|
||||||
|
void SIM800L::initInternalBuffer() {
|
||||||
|
for(uint16_t i = 0; i < internalBufferSize; i++) {
|
||||||
|
internalBuffer[i] = '\0';
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Init recv buffer
|
||||||
|
*/
|
||||||
|
void SIM800L::initRecvBuffer() {
|
||||||
|
// Cleanup the receive buffer
|
||||||
|
for(uint16_t i = 0; i < recvBufferSize; i++) {
|
||||||
|
recvBuffer[i] = 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/*****************************************************************************************
|
||||||
|
* LOW LEVEL FUNCTIONS TO COMMUNICATE WITH THE SIM800L MODULE
|
||||||
|
*****************************************************************************************/
|
||||||
|
/**
|
||||||
|
* Send AT command to the module
|
||||||
|
*/
|
||||||
|
void SIM800L::sendCommand(const char* command) {
|
||||||
|
if(enableDebug) {
|
||||||
|
debugStream->print(F("SIM800L : Send \""));
|
||||||
|
debugStream->print(command);
|
||||||
|
debugStream->println(F("\""));
|
||||||
|
}
|
||||||
|
|
||||||
|
purgeSerial();
|
||||||
|
stream->write(command);
|
||||||
|
stream->write("\r\n");
|
||||||
|
purgeSerial();
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Send AT command coming from the PROGMEM
|
||||||
|
*/
|
||||||
|
void SIM800L::sendCommand_P(const char* command) {
|
||||||
|
char cmdBuff[32];
|
||||||
|
strcpy_P(cmdBuff, command);
|
||||||
|
sendCommand(cmdBuff);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Send AT command to the module with a parameter
|
||||||
|
*/
|
||||||
|
void SIM800L::sendCommand(const char* command, const char* parameter) {
|
||||||
|
if(enableDebug) {
|
||||||
|
debugStream->print(F("SIM800L : Send \""));
|
||||||
|
debugStream->print(command);
|
||||||
|
debugStream->print(F("\""));
|
||||||
|
debugStream->print(parameter);
|
||||||
|
debugStream->print(F("\""));
|
||||||
|
debugStream->println(F("\""));
|
||||||
|
}
|
||||||
|
|
||||||
|
purgeSerial();
|
||||||
|
stream->write(command);
|
||||||
|
stream->write("\"");
|
||||||
|
stream->write(parameter);
|
||||||
|
stream->write("\"");
|
||||||
|
stream->write("\r\n");
|
||||||
|
purgeSerial();
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Send AT command coming from the PROGMEM with a parameter
|
||||||
|
*/
|
||||||
|
void SIM800L::sendCommand_P(const char* command, const char* parameter) {
|
||||||
|
char cmdBuff[32];
|
||||||
|
strcpy_P(cmdBuff, command);
|
||||||
|
sendCommand(cmdBuff, parameter);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Purge the serial data
|
||||||
|
*/
|
||||||
|
void SIM800L::purgeSerial() {
|
||||||
|
stream->flush();
|
||||||
|
while (stream->available()) {
|
||||||
|
stream->read();
|
||||||
|
}
|
||||||
|
stream->flush();
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Read from module and expect a specific answer (timeout in millisec)
|
||||||
|
*/
|
||||||
|
bool SIM800L::readResponseCheckAnswer_P(uint16_t timeout, const char* expectedAnswer, uint8_t crlfToWait) {
|
||||||
|
if(readResponse(timeout, crlfToWait)) {
|
||||||
|
// Prepare the local expected answer
|
||||||
|
char rspBuff[16];
|
||||||
|
strcpy_P(rspBuff, expectedAnswer);
|
||||||
|
|
||||||
|
// Check if it's the expected answer
|
||||||
|
int16_t idx = strIndex(internalBuffer, rspBuff);
|
||||||
|
if(idx > 0) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Read from the module for a specific number of CRLF
|
||||||
|
* True if we have some data
|
||||||
|
*/
|
||||||
|
bool SIM800L::readResponse(uint16_t timeout, uint8_t crlfToWait) {
|
||||||
|
uint16_t currentSizeResponse = 0;
|
||||||
|
bool seenCR = false;
|
||||||
|
uint8_t countCRLF = 0;
|
||||||
|
|
||||||
|
// First of all, cleanup the buffer
|
||||||
|
initInternalBuffer();
|
||||||
|
|
||||||
|
uint32_t timerStart = millis();
|
||||||
|
|
||||||
|
while(1) {
|
||||||
|
// While there is data available on the buffer, read it until the max size of the response
|
||||||
|
if(stream->available()) {
|
||||||
|
// Load the next char
|
||||||
|
internalBuffer[currentSizeResponse] = stream->read();
|
||||||
|
|
||||||
|
// Detect end of transmission (CRLF)
|
||||||
|
if(internalBuffer[currentSizeResponse] == '\r') {
|
||||||
|
seenCR = true;
|
||||||
|
} else if (internalBuffer[currentSizeResponse] == '\n' && seenCR) {
|
||||||
|
countCRLF++;
|
||||||
|
if(countCRLF == crlfToWait) {
|
||||||
|
if(enableDebug) debugStream->println(F("SIM800L : End of transmission"));
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
seenCR = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Prepare for next read
|
||||||
|
currentSizeResponse++;
|
||||||
|
|
||||||
|
// Avoid buffer overflow
|
||||||
|
if(currentSizeResponse == internalBufferSize) {
|
||||||
|
if(enableDebug) debugStream->println(F("SIM800L : Received maximum buffer size"));
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// If timeout, abord the reading
|
||||||
|
if(millis() - timerStart > timeout) {
|
||||||
|
if(enableDebug) debugStream->println(F("SIM800L : Receive timeout"));
|
||||||
|
// Timeout, return false to parent function
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if(enableDebug) {
|
||||||
|
debugStream->print(F("SIM800L : Receive \""));
|
||||||
|
debugStream->print(internalBuffer);
|
||||||
|
debugStream->println(F("\""));
|
||||||
|
}
|
||||||
|
|
||||||
|
// If we are here, it's OK ;-)
|
||||||
|
return true;
|
||||||
|
}
|
||||||
139
SIM800L.h
Normal file
139
SIM800L.h
Normal file
@@ -0,0 +1,139 @@
|
|||||||
|
/********************************************************************************
|
||||||
|
* Arduino-SIM800L-driver *
|
||||||
|
* ---------------------- *
|
||||||
|
* Arduino driver for GSM/GPRS module SIMCom SIM800L to make HTTP/S connections *
|
||||||
|
* with GET and POST methods *
|
||||||
|
* Author: Olivier Staquet *
|
||||||
|
* Last version available on https://github.com/ostaquet/Arduino-SIM800L-driver *
|
||||||
|
********************************************************************************
|
||||||
|
* MIT License
|
||||||
|
*
|
||||||
|
* Copyright (c) 2019 Olivier Staquet
|
||||||
|
*
|
||||||
|
* Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||||
|
* of this software and associated documentation files (the "Software"), to deal
|
||||||
|
* in the Software without restriction, including without limitation the rights
|
||||||
|
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||||
|
* copies of the Software, and to permit persons to whom the Software is
|
||||||
|
* furnished to do so, subject to the following conditions:
|
||||||
|
*
|
||||||
|
* The above copyright notice and this permission notice shall be included in all
|
||||||
|
* copies or substantial portions of the Software.
|
||||||
|
*
|
||||||
|
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||||
|
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||||
|
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||||
|
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||||
|
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||||
|
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
|
||||||
|
* SOFTWARE.
|
||||||
|
*******************************************************************************/
|
||||||
|
#ifndef _SIM800L_H_
|
||||||
|
#define _SIM800L_H_
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
|
||||||
|
#define DEFAULT_TIMEOUT 5000
|
||||||
|
#define RESET_PIN_NOT_USED -1
|
||||||
|
|
||||||
|
enum PowerMode {MINIMUM, NORMAL, POW_UNKNOWN, SLEEP, POW_ERROR};
|
||||||
|
enum NetworkRegistration {NOT_REGISTERED, REGISTERED_HOME, SEARCHING, DENIED, NET_UNKNOWN, REGISTERED_ROAMING, NET_ERROR};
|
||||||
|
|
||||||
|
class SIM800L {
|
||||||
|
public:
|
||||||
|
// Initialize the driver
|
||||||
|
// Parameters:
|
||||||
|
// _stream : Stream opened to the SIM800L module (Software or Hardware, usually 9600 bps)
|
||||||
|
// _pinRst (optional) : pin to the reset of the SIM800L module
|
||||||
|
// _internalBufferSize (optional): size in bytes of the internal buffer to handle general IO with the module
|
||||||
|
// (including URL and maximum payload to send through POST method)
|
||||||
|
// _recvBufferSize (optional) : size in bytes of the reception buffer (max data to receive from GET or POST)
|
||||||
|
// _debugStream (optional) : Stream opened to the debug console (Software of Hardware)
|
||||||
|
SIM800L(Stream* _stream, uint8_t _pinRst = RESET_PIN_NOT_USED, uint16_t _internalBufferSize = 128, uint16_t _recvBufferSize = 256, Stream* _debugStream = NULL);
|
||||||
|
~SIM800L();
|
||||||
|
|
||||||
|
// Force a reset of the module
|
||||||
|
void reset();
|
||||||
|
|
||||||
|
// Status functions
|
||||||
|
bool isReady();
|
||||||
|
uint8_t getSignal();
|
||||||
|
PowerMode getPowerMode();
|
||||||
|
NetworkRegistration getRegistrationStatus();
|
||||||
|
char* getVersion();
|
||||||
|
char* getFirmware();
|
||||||
|
char* getSimCardNumber();
|
||||||
|
|
||||||
|
// Define the power mode (for parameter: see PowerMode enum)
|
||||||
|
bool setPowerMode(PowerMode powerMode);
|
||||||
|
|
||||||
|
// Enable/disable GPRS
|
||||||
|
bool setupGPRS(const char *apn);
|
||||||
|
bool connectGPRS();
|
||||||
|
bool isConnectedGPRS();
|
||||||
|
bool disconnectGPRS();
|
||||||
|
|
||||||
|
// HTTP methods
|
||||||
|
uint16_t doGet(const char* url, uint16_t serverReadTimeoutMs);
|
||||||
|
uint16_t doGet(const char* url, const char* headers, uint16_t serverReadTimeoutMs);
|
||||||
|
uint16_t doPost(const char* url, const char* contentType, const char* payload, uint16_t clientWriteTimeoutMs, uint16_t serverReadTimeoutMs);
|
||||||
|
uint16_t doPost(const char* url, const char* headers, const char* contentType, const char* payload, uint16_t clientWriteTimeoutMs, uint16_t serverReadTimeoutMs);
|
||||||
|
|
||||||
|
// Obtain results after HTTP successful connections (size and buffer)
|
||||||
|
uint16_t getDataSizeReceived();
|
||||||
|
char* getDataReceived();
|
||||||
|
|
||||||
|
protected:
|
||||||
|
// Send command
|
||||||
|
void sendCommand(const char* command);
|
||||||
|
// Send comment from PROGMEM
|
||||||
|
void sendCommand_P(const char* command);
|
||||||
|
// Send command with parameter within quotes (template : command"parameter")
|
||||||
|
void sendCommand(const char* command, const char* parameter);
|
||||||
|
// Send command with parameter within quotes from PROGMEM (template : command"parameter")
|
||||||
|
void sendCommand_P(const char* command, const char* parameter);
|
||||||
|
|
||||||
|
// Read from module (timeout in millisec)
|
||||||
|
bool readResponse(uint16_t timeout, uint8_t crlfToWait = 2);
|
||||||
|
// Read from module and expect a specific answer defined in PROGMEM (timeout in millisec)
|
||||||
|
bool readResponseCheckAnswer_P(uint16_t timeout, const char* expectedAnswer, uint8_t crlfToWait = 2);
|
||||||
|
|
||||||
|
// Purge the serial
|
||||||
|
void purgeSerial();
|
||||||
|
|
||||||
|
// Find string in another string
|
||||||
|
int16_t strIndex(const char* str, const char* findStr, uint16_t startIdx = 0);
|
||||||
|
|
||||||
|
// Manage internal buffer
|
||||||
|
void initInternalBuffer();
|
||||||
|
void initRecvBuffer();
|
||||||
|
|
||||||
|
// Initiate HTTP/S connection
|
||||||
|
uint16_t initiateHTTP(const char* url, const char* headers);
|
||||||
|
uint16_t terminateHTTP();
|
||||||
|
|
||||||
|
private:
|
||||||
|
// Serial line with SIM800L
|
||||||
|
Stream* stream = NULL;
|
||||||
|
|
||||||
|
// Serial console for the debug
|
||||||
|
Stream* debugStream = NULL;
|
||||||
|
|
||||||
|
// Details about the circuit: pins
|
||||||
|
uint8_t pinReset = 0;
|
||||||
|
|
||||||
|
// Internal memory for the shared buffer
|
||||||
|
// Used for all reception of message from the module
|
||||||
|
char *internalBuffer;
|
||||||
|
uint16_t internalBufferSize = 0;
|
||||||
|
|
||||||
|
// Reception buffer
|
||||||
|
char *recvBuffer;
|
||||||
|
uint16_t recvBufferSize = 0;
|
||||||
|
uint16_t dataSize = 0;
|
||||||
|
|
||||||
|
// Enable debug mode
|
||||||
|
bool enableDebug = false;
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif // _SIM800L_H_
|
||||||
@@ -1,7 +1,7 @@
|
|||||||
|
|
||||||
rem slow GUI performance via arduino-cli yet
|
rem slow GUI performance via arduino-cli yet
|
||||||
|
|
||||||
arduino-cli compile -v -b esp32:esp32:esp32wrover --build-properties build.extra_flags=-BOARD_TTGO_T4=1 -v evDash.ino
|
rem arduino-cli compile -v -b esp32:esp32:esp32wrover --build-properties build.extra_flags=-BOARD_TTGO_T4=1 -v evDash.ino
|
||||||
rem arduino-cli compile -v -b esp32:esp32:esp32:PSRAM=enabled,PartitionScheme=huge_app,CPUFreq=80 --build-properties build.extra_flags=-BOARD_TTGO_T4=1 -v evDash.ino
|
rem arduino-cli compile -v -b esp32:esp32:esp32:PSRAM=enabled,PartitionScheme=huge_app,CPUFreq=80 --build-properties build.extra_flags=-BOARD_TTGO_T4=1 -v evDash.ino
|
||||||
rem rduino-cli upload -b esp32:esp32:esp32 -v -p COM6
|
rem rduino-cli upload -b esp32:esp32:esp32 -v -p COM6
|
||||||
|
|
||||||
@@ -11,4 +11,8 @@ rem arduino-cli upload -v -b esp32:esp32:m5stack-core-esp32 -p COM9
|
|||||||
rem arduino-cli compile -v -b esp32:esp32:esp32:PSRAM=enabled,PartitionScheme=huge_app,CPUFreq=80 --build-properties build.extra_flags=-BOARD_M5STACK=1 -v evDash.ino
|
rem arduino-cli compile -v -b esp32:esp32:esp32:PSRAM=enabled,PartitionScheme=huge_app,CPUFreq=80 --build-properties build.extra_flags=-BOARD_M5STACK=1 -v evDash.ino
|
||||||
rem arduino-cli upload -b esp32:esp32:esp32 -v -p COM9
|
rem arduino-cli upload -b esp32:esp32:esp32 -v -p COM9
|
||||||
|
|
||||||
|
arduino-cli compile -v -b esp32:esp32:esp32wrover -v evDash.ino
|
||||||
|
arduino-cli upload -b esp32:esp32:esp32wrover -v -p COM8
|
||||||
|
|
||||||
|
|
||||||
pause
|
pause
|
||||||
37
config.h
37
config.h
@@ -3,8 +3,8 @@
|
|||||||
|
|
||||||
#include <BLEDevice.h>
|
#include <BLEDevice.h>
|
||||||
|
|
||||||
#define APP_VERSION "v2.0.0"
|
#define APP_VERSION "v2.1.1"
|
||||||
#define APP_RELEASE_DATE "2020-12-02"
|
#define APP_RELEASE_DATE "2020-12-14"
|
||||||
|
|
||||||
// TFT COLORS FOR TTGO
|
// TFT COLORS FOR TTGO
|
||||||
#define TFT_BLACK 0x0000 /* 0, 0, 0 */
|
#define TFT_BLACK 0x0000 /* 0, 0, 0 */
|
||||||
@@ -53,7 +53,7 @@
|
|||||||
#define SIM800L_RX 16
|
#define SIM800L_RX 16
|
||||||
#define SIM800L_TX 17
|
#define SIM800L_TX 17
|
||||||
#define SIM800L_RST 5
|
#define SIM800L_RST 5
|
||||||
#define SIM800L_TIMER 120
|
#define SIM800L_TIMER 60
|
||||||
#endif //SIM800L_ENABLED
|
#endif //SIM800L_ENABLED
|
||||||
|
|
||||||
// MENU ITEM
|
// MENU ITEM
|
||||||
@@ -66,4 +66,35 @@ typedef struct {
|
|||||||
char serviceUUID[40];
|
char serviceUUID[40];
|
||||||
} MENU_ITEM;
|
} MENU_ITEM;
|
||||||
|
|
||||||
|
#define MENU_VEHICLE_TYPE 1
|
||||||
|
#define MENU_SAVE_SETTINGS 9
|
||||||
|
#define MENU_APP_VERSION 10
|
||||||
|
//
|
||||||
|
#define MENU_WIFI 301
|
||||||
|
#define MENU_GPRS 302
|
||||||
|
#define MENU_NTP 303
|
||||||
|
#define MENU_SDCARD 304
|
||||||
|
#define MENU_SCREEN_ROTATION 305
|
||||||
|
#define MENU_DEFAULT_SCREEN 306
|
||||||
|
#define MENU_SCREEN_BRIGHTNESS 307
|
||||||
|
#define MENU_PREDRAWN_GRAPHS 308
|
||||||
|
#define MENU_REMOTE_UPLOAD 309
|
||||||
|
#define MENU_HEADLIGHTS_REMINDER 310
|
||||||
|
#define MENU_DEBUG_SCREEN 311
|
||||||
|
#define MENU_GPS 312
|
||||||
|
//
|
||||||
|
#define MENU_DISTANCE_UNIT 401
|
||||||
|
#define MENU_TEMPERATURE_UNIT 402
|
||||||
|
#define MENU_PRESSURE_UNIT 403
|
||||||
|
//
|
||||||
|
#define MENU_WIFI_ENABLED 3011
|
||||||
|
#define MENU_WIFI_SSID 3012
|
||||||
|
#define MENU_WIFI_PASSWORD 3013
|
||||||
|
//
|
||||||
|
#define MENU_SDCARD_ENABLED 3041
|
||||||
|
#define MENU_SDCARD_AUTOSTARTLOG 3042
|
||||||
|
#define MENU_SDCARD_MOUNT_STATUS 3043
|
||||||
|
#define MENU_SDCARD_REC 3044
|
||||||
|
//
|
||||||
|
|
||||||
#endif // CONFIG_H
|
#endif // CONFIG_H
|
||||||
|
|||||||
BIN
dist/m5stack_core1/evDash.ino.bin
vendored
BIN
dist/m5stack_core1/evDash.ino.bin
vendored
Binary file not shown.
BIN
dist/ttgo_t4_v13/evDash.ino.bin
vendored
BIN
dist/ttgo_t4_v13/evDash.ino.bin
vendored
Binary file not shown.
209
evDash.ino
209
evDash.ino
@@ -1,18 +1,29 @@
|
|||||||
/*
|
/*
|
||||||
* 2020-12-02
|
Project renamed from eNiroDashboard to evDash
|
||||||
* Project renamed from eNiroDashboard to evDash
|
|
||||||
*
|
|
||||||
!! working only with OBD BLE 4.0 adapters
|
!! working only with OBD BLE 4.0 adapters
|
||||||
!! Supported adapter is Vgate ICar Pro (must be BLE4.0 version)
|
!! Supported adapter is Vgate ICar Pro (must be BLE4.0 version)
|
||||||
!! Not working with standard BLUETOOTH 3 adapters
|
!! Not working with standard BLUETOOTH 3 adapters
|
||||||
|
|
||||||
|
Serial console commands
|
||||||
|
|
||||||
|
serviceUUID=xxx
|
||||||
|
charTxUUID=xxx
|
||||||
|
charRxUUID=xxx
|
||||||
|
wifiSsid=xxx
|
||||||
|
wifiPassword=xxx
|
||||||
|
gprsApn=xxx
|
||||||
|
remoteApiUrl=xxx
|
||||||
|
remoteApiKey=xxx
|
||||||
|
|
||||||
Required libraries
|
Required libraries
|
||||||
- esp32 board support
|
- esp32 board support
|
||||||
- tft_espi
|
- tft_espi
|
||||||
- ArduinoJson
|
- ArduinoJson
|
||||||
|
- TinyGPSPlus (m5stack GPS)
|
||||||
|
|
||||||
SIM800L m5stack (https://github.com/kolaCZek)
|
SIM800L m5stack (https://github.com/kolaCZek)
|
||||||
- SIM800L.h, SoftwareSerial.h
|
- SIM800L.h
|
||||||
*/
|
*/
|
||||||
|
|
||||||
////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////
|
||||||
@@ -24,13 +35,11 @@
|
|||||||
//#define BOARD_M5STACK_CORE
|
//#define BOARD_M5STACK_CORE
|
||||||
|
|
||||||
//#define SIM800L_ENABLED
|
//#define SIM800L_ENABLED
|
||||||
//#define SD_ENABLED
|
|
||||||
|
|
||||||
////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////
|
||||||
////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////
|
||||||
|
|
||||||
#include <SPI.h>
|
#include <SPI.h>
|
||||||
#include <BLEDevice.h>
|
|
||||||
#include "BoardInterface.h"
|
#include "BoardInterface.h"
|
||||||
|
|
||||||
#ifdef BOARD_TTGO_T4
|
#ifdef BOARD_TTGO_T4
|
||||||
@@ -40,30 +49,25 @@
|
|||||||
#include "BoardM5stackCore.h"
|
#include "BoardM5stackCore.h"
|
||||||
#endif // BOARD_M5STACK_CORE
|
#endif // BOARD_M5STACK_CORE
|
||||||
|
|
||||||
#ifdef SD_ENABLED
|
#include <BLEDevice.h>
|
||||||
#include <mySD.h>
|
|
||||||
//#include <SD.h>
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#include <sys/time.h>
|
#include <sys/time.h>
|
||||||
#include "config.h"
|
#include "config.h"
|
||||||
#include "LiveData.h"
|
#include "LiveData.h"
|
||||||
#include "CarInterface.h"
|
#include "CarInterface.h"
|
||||||
#include "CarKiaEniro.h"
|
#include "CarKiaEniro.h"
|
||||||
#include "CarHyundaiIoniq.h"
|
#include "CarHyundaiIoniq.h"
|
||||||
|
#include "CarRenaultZoe.h"
|
||||||
|
#include "CarKiaNiroPhev.h"
|
||||||
#include "CarKiaDebugObd2.h"
|
#include "CarKiaDebugObd2.h"
|
||||||
|
|
||||||
#ifdef SIM800L_ENABLED
|
#ifdef SIM800L_ENABLED
|
||||||
#include <ArduinoJson.h>
|
#include <ArduinoJson.h>
|
||||||
#include <SoftwareSerial.h>
|
|
||||||
#include "SIM800L.h"
|
#include "SIM800L.h"
|
||||||
|
|
||||||
SIM800L* sim800l;
|
SIM800L* sim800l;
|
||||||
|
HardwareSerial SerialGPRS(2);
|
||||||
#endif //SIM800L_ENABLED
|
#endif //SIM800L_ENABLED
|
||||||
|
|
||||||
// PLEASE CHANGE THIS SETTING for your BLE4
|
|
||||||
uint32_t PIN = 1234;
|
|
||||||
|
|
||||||
// Temporary variables
|
// Temporary variables
|
||||||
char ch;
|
char ch;
|
||||||
String line;
|
String line;
|
||||||
@@ -82,6 +86,8 @@ bool doNextAtCommand() {
|
|||||||
if (liveData->commandQueueIndex >= liveData->commandQueueCount) {
|
if (liveData->commandQueueIndex >= liveData->commandQueueCount) {
|
||||||
liveData->commandQueueIndex = liveData->commandQueueLoopFrom;
|
liveData->commandQueueIndex = liveData->commandQueueLoopFrom;
|
||||||
board->redrawScreen();
|
board->redrawScreen();
|
||||||
|
// log every queue loop (temp)
|
||||||
|
liveData->params.sdcardCanNotify = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Send AT command to obd
|
// Send AT command to obd
|
||||||
@@ -213,6 +219,8 @@ class MyAdvertisedDeviceCallbacks: public BLEAdvertisedDeviceCallbacks {
|
|||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
uint32_t PIN = 1234;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
BLE Security
|
BLE Security
|
||||||
*/
|
*/
|
||||||
@@ -365,7 +373,7 @@ void startBleScan() {
|
|||||||
|
|
||||||
liveData->foundMyBleDevice = NULL;
|
liveData->foundMyBleDevice = NULL;
|
||||||
liveData->scanningDeviceIndex = 0;
|
liveData->scanningDeviceIndex = 0;
|
||||||
board->displayMessage(" > Scanning BLE4 devices", "40 seconds");
|
board->displayMessage(" > Scanning BLE4 devices", "40sec.or hold middle&RST");
|
||||||
|
|
||||||
// Start scanning
|
// Start scanning
|
||||||
Serial.println("Scanning BLE devices...");
|
Serial.println("Scanning BLE devices...");
|
||||||
@@ -402,11 +410,14 @@ void startBleScan() {
|
|||||||
SIM800L
|
SIM800L
|
||||||
*/
|
*/
|
||||||
#ifdef SIM800L_ENABLED
|
#ifdef SIM800L_ENABLED
|
||||||
bool sim800lSetup() {
|
bool sim800lSetup() {
|
||||||
Serial.println("Setting SIM800L module");
|
Serial.println("Setting SIM800L module");
|
||||||
SoftwareSerial* serial = new SoftwareSerial(SIM800L_RX, SIM800L_TX);
|
|
||||||
serial->begin(9600);
|
SerialGPRS.begin(9600);
|
||||||
sim800l = new SIM800L((Stream *)serial, SIM800L_RST, 512 , 512);
|
|
||||||
|
sim800l = new SIM800L((Stream *)&SerialGPRS, SIM800L_RST, 512 , 512);
|
||||||
|
// SIM800L DebugMode:
|
||||||
|
//sim800l = new SIM800L((Stream *)&SerialGPRS, SIM800L_RST, 512 , 512, (Stream *)&Serial);
|
||||||
|
|
||||||
bool sim800l_ready = sim800l->isReady();
|
bool sim800l_ready = sim800l->isReady();
|
||||||
for (uint8_t i = 0; i < 5 && !sim800l_ready; i++) {
|
for (uint8_t i = 0; i < 5 && !sim800l_ready; i++) {
|
||||||
@@ -415,26 +426,26 @@ bool sim800lSetup() {
|
|||||||
sim800l_ready = sim800l->isReady();
|
sim800l_ready = sim800l->isReady();
|
||||||
}
|
}
|
||||||
|
|
||||||
if(!sim800l_ready) {
|
if (!sim800l_ready) {
|
||||||
Serial.println("Problem to initialize SIM800L module");
|
Serial.println("Problem to initialize SIM800L module");
|
||||||
} else {
|
} else {
|
||||||
Serial.println("SIM800L module initialized");
|
Serial.println("SIM800L module initialized");
|
||||||
|
|
||||||
Serial.print("Setting GPRS APN to: ");
|
Serial.print("Setting GPRS APN to: ");
|
||||||
Serial.println(liveData->settings.gprsApn);
|
Serial.println(liveData->settings.gprsApn);
|
||||||
|
|
||||||
bool sim800l_gprs = sim800l->setupGPRS(liveData->settings.gprsApn);
|
bool sim800l_gprs = sim800l->setupGPRS(liveData->settings.gprsApn);
|
||||||
for(uint8_t i = 0; i < 5 && !sim800l_gprs; i++) {
|
for (uint8_t i = 0; i < 5 && !sim800l_gprs; i++) {
|
||||||
Serial.println("Problem to set GPRS connection, retry in 1 sec");
|
Serial.println("Problem to set GPRS APN, retry in 1 sec");
|
||||||
delay(1000);
|
delay(1000);
|
||||||
sim800l_gprs = sim800l->setupGPRS(liveData->settings.gprsApn);
|
sim800l_gprs = sim800l->setupGPRS(liveData->settings.gprsApn);
|
||||||
}
|
}
|
||||||
|
|
||||||
if(sim800l_gprs) {
|
if (sim800l_gprs) {
|
||||||
liveData->params.sim800l_enabled = true;
|
liveData->params.sim800l_enabled = true;
|
||||||
Serial.println("GPRS OK");
|
Serial.println("GPRS APN set OK");
|
||||||
} else {
|
} else {
|
||||||
Serial.println("Problem to set GPRS");
|
Serial.println("Problem to set GPRS APN");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -446,62 +457,68 @@ bool sendDataViaGPRS() {
|
|||||||
|
|
||||||
NetworkRegistration network = sim800l->getRegistrationStatus();
|
NetworkRegistration network = sim800l->getRegistrationStatus();
|
||||||
if (network != REGISTERED_HOME && network != REGISTERED_ROAMING) {
|
if (network != REGISTERED_HOME && network != REGISTERED_ROAMING) {
|
||||||
Serial.println("SIM800L module not connected to network!");
|
Serial.println("SIM800L module not connected to network, skipping data send");
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool connected = sim800l->connectGPRS();
|
if(!sim800l->isConnectedGPRS()) {
|
||||||
for (uint8_t i = 0; i < 5 && !connected; i++) {
|
Serial.println("GPRS not connected... Connecting");
|
||||||
delay(1000);
|
bool connected = sim800l->connectGPRS();
|
||||||
connected = sim800l->connectGPRS();
|
for (uint8_t i = 0; i < 5 && !connected; i++) {
|
||||||
}
|
Serial.println("Problem to connect GPRS, retry in 1 sec");
|
||||||
|
delay(1000);
|
||||||
|
connected = sim800l->connectGPRS();
|
||||||
|
}
|
||||||
|
if(connected) {
|
||||||
|
Serial.println("GPRS connected!");
|
||||||
|
} else {
|
||||||
|
Serial.println("GPRS not connected! Reseting SIM800L module!");
|
||||||
|
sim800l->reset();
|
||||||
|
sim800lSetup();
|
||||||
|
|
||||||
if (!connected) {
|
return false;
|
||||||
Serial.println("GPRS not connected! Reseting SIM800L module!");
|
}
|
||||||
sim800l->reset();
|
|
||||||
sim800lSetup();
|
|
||||||
|
|
||||||
return false;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
Serial.println("Start HTTP POST...");
|
Serial.println("Start HTTP POST...");
|
||||||
|
|
||||||
StaticJsonDocument<250> jsonData;
|
StaticJsonDocument<512> jsonData;
|
||||||
|
|
||||||
jsonData["akey"] = liveData->settings.remoteApiKey;
|
jsonData["apikey"] = liveData->settings.remoteApiKey;
|
||||||
jsonData["soc"] = liveData->params.socPerc;
|
jsonData["carType"] = liveData->settings.carType;
|
||||||
jsonData["soh"] = liveData->params.sohPerc;
|
jsonData["socPerc"] = liveData->params.socPerc;
|
||||||
jsonData["batK"] = liveData->params.batPowerKw;
|
jsonData["sohPerc"] = liveData->params.sohPerc;
|
||||||
jsonData["batA"] = liveData->params.batPowerAmp;
|
jsonData["batPowerKw"] = liveData->params.batPowerKw;
|
||||||
jsonData["batV"] = liveData->params.batVoltage;
|
jsonData["batPowerAmp"] = liveData->params.batPowerAmp;
|
||||||
jsonData["auxV"] = liveData->params.auxVoltage;
|
jsonData["batVoltage"] = liveData->params.batVoltage;
|
||||||
jsonData["MinC"] = liveData->params.batMinC;
|
jsonData["auxVoltage"] = liveData->params.auxVoltage;
|
||||||
jsonData["MaxC"] = liveData->params.batMaxC;
|
jsonData["auxAmp"] = liveData->params.auxCurrentAmp;
|
||||||
jsonData["InlC"] = liveData->params.batInletC;
|
jsonData["batMinC"] = liveData->params.batMinC;
|
||||||
jsonData["fan"] = liveData->params.batFanStatus;
|
jsonData["batMaxC"] = liveData->params.batMaxC;
|
||||||
jsonData["cumCh"] = liveData->params.cumulativeEnergyChargedKWh;
|
jsonData["batInletC"] = liveData->params.batInletC;
|
||||||
jsonData["cumD"] = liveData->params.cumulativeEnergyDischargedKWh;
|
jsonData["batFanStatus"] = liveData->params.batFanStatus;
|
||||||
|
jsonData["speedKmh"] = liveData->params.speedKmh;
|
||||||
|
jsonData["cumulativeEnergyChargedKWh"] = liveData->params.cumulativeEnergyChargedKWh;
|
||||||
|
jsonData["cumulativeEnergyDischargedKWh"] = liveData->params.cumulativeEnergyDischargedKWh;
|
||||||
|
|
||||||
char payload[200];
|
char payload[512];
|
||||||
serializeJson(jsonData, payload);
|
serializeJson(jsonData, payload);
|
||||||
|
|
||||||
Serial.print("Sending payload: ");
|
Serial.print("Sending payload: ");
|
||||||
Serial.println(payload);
|
Serial.println(payload);
|
||||||
|
|
||||||
Serial.print("Remote API server: ");
|
Serial.print("Remote API server: ");
|
||||||
Serial.println(liveData->settings.remoteApiSrvr);
|
Serial.println(liveData->settings.remoteApiUrl);
|
||||||
|
|
||||||
uint16_t rc = sim800l->doPost(liveData->settings.remoteApiSrvr, "application/json", payload, 10000, 10000);
|
uint16_t rc = sim800l->doPost(liveData->settings.remoteApiUrl, "application/json", payload, 10000, 10000);
|
||||||
if(rc == 200) {
|
if (rc == 200) {
|
||||||
Serial.println(F("HTTP POST successful"));
|
Serial.println("HTTP POST successful");
|
||||||
} else {
|
} else {
|
||||||
// Failed...
|
// Failed...
|
||||||
Serial.print(F("HTTP POST error: "));
|
Serial.print("HTTP POST error: ");
|
||||||
Serial.println(rc);
|
Serial.println(rc);
|
||||||
}
|
}
|
||||||
|
|
||||||
sim800l->disconnectGPRS();
|
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
#endif //SIM800L_ENABLED
|
#endif //SIM800L_ENABLED
|
||||||
@@ -517,6 +534,7 @@ void setup(void) {
|
|||||||
Serial.println("Booting device...");
|
Serial.println("Booting device...");
|
||||||
|
|
||||||
// Init settings/params, board library
|
// Init settings/params, board library
|
||||||
|
line = "";
|
||||||
liveData = new LiveData();
|
liveData = new LiveData();
|
||||||
liveData->initParams();
|
liveData->initParams();
|
||||||
|
|
||||||
@@ -536,6 +554,10 @@ void setup(void) {
|
|||||||
car = new CarKiaEniro();
|
car = new CarKiaEniro();
|
||||||
} else if (liveData->settings.carType == CAR_HYUNDAI_IONIQ_2018) {
|
} else if (liveData->settings.carType == CAR_HYUNDAI_IONIQ_2018) {
|
||||||
car = new CarHyundaiIoniq();
|
car = new CarHyundaiIoniq();
|
||||||
|
} else if (liveData->settings.carType == CAR_KIA_NIRO_PHEV) {
|
||||||
|
car = new CarKiaNiroPhev();
|
||||||
|
} else if (liveData->settings.carType == CAR_RENAULT_ZOE) {
|
||||||
|
car = new CarRenaultZoe();
|
||||||
} else {
|
} else {
|
||||||
// if (liveData->settings.carType == CAR_DEBUG_OBD2_KIA)
|
// if (liveData->settings.carType == CAR_DEBUG_OBD2_KIA)
|
||||||
car = new CarKiaDebugObd2();
|
car = new CarKiaDebugObd2();
|
||||||
@@ -556,27 +578,9 @@ void setup(void) {
|
|||||||
getLocalTime(&now, 0);
|
getLocalTime(&now, 0);
|
||||||
liveData->params.chargingStartTime = liveData->params.currentTime = mktime(&now);
|
liveData->params.chargingStartTime = liveData->params.currentTime = mktime(&now);
|
||||||
|
|
||||||
// Hold right button
|
|
||||||
board->afterSetup();
|
|
||||||
|
|
||||||
#ifdef SD_ENABLED
|
|
||||||
// Init SDCARD
|
|
||||||
/*if (!SD.begin(SD_CS, SD_MOSI, SD_MISO, SD_SCLK)) {
|
|
||||||
Serial.println("SDCARD initialization failed!");
|
|
||||||
} else {
|
|
||||||
Serial.println("SDCARD initialization done.");
|
|
||||||
}
|
|
||||||
/*spiSD.begin(SD_SCLK,SD_MISO,SD_MOSI,SD_CS);
|
|
||||||
if(!SD.begin( SD_CS, spiSD, 27000000)){
|
|
||||||
Serial.println("SDCARD initialization failed!");
|
|
||||||
} else {
|
|
||||||
Serial.println("SDCARD initialization done.");
|
|
||||||
}*/
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// Start BLE connection
|
// Start BLE connection
|
||||||
line = "";
|
|
||||||
Serial.println("Start BLE with PIN auth");
|
Serial.println("Start BLE with PIN auth");
|
||||||
|
ESP_ERROR_CHECK(esp_bt_controller_mem_release(ESP_BT_MODE_CLASSIC_BT));
|
||||||
BLEDevice::init("");
|
BLEDevice::init("");
|
||||||
|
|
||||||
// Retrieve a Scanner and set the callback we want to use to be informed when we have detected a new device.
|
// Retrieve a Scanner and set the callback we want to use to be informed when we have detected a new device.
|
||||||
@@ -589,7 +593,8 @@ void setup(void) {
|
|||||||
liveData->pBLEScan->setActiveScan(true);
|
liveData->pBLEScan->setActiveScan(true);
|
||||||
|
|
||||||
// Skip BLE scan if middle button pressed
|
// Skip BLE scan if middle button pressed
|
||||||
if (!board->skipAdapterScan()) {
|
if (strcmp(liveData->settings.obdMacAddress, "00:00:00:00:00:00") != 0 && !board->skipAdapterScan()) {
|
||||||
|
Serial.println(liveData->settings.obdMacAddress);
|
||||||
startBleScan();
|
startBleScan();
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -597,6 +602,9 @@ void setup(void) {
|
|||||||
sim800lSetup();
|
sim800lSetup();
|
||||||
#endif //SIM800L_ENABLED
|
#endif //SIM800L_ENABLED
|
||||||
|
|
||||||
|
// Hold right button
|
||||||
|
board->afterSetup();
|
||||||
|
|
||||||
// End
|
// End
|
||||||
Serial.println("Device setup completed");
|
Serial.println("Device setup completed");
|
||||||
}
|
}
|
||||||
@@ -627,40 +635,35 @@ void loop() {
|
|||||||
}
|
}
|
||||||
|
|
||||||
// Send command from TTY to OBD2
|
// Send command from TTY to OBD2
|
||||||
if (liveData->bleConnected) {
|
if (Serial.available()) {
|
||||||
if (Serial.available()) {
|
ch = Serial.read();
|
||||||
ch = Serial.read();
|
if (ch == '\r' || ch == '\n') {
|
||||||
|
board->customConsoleCommand(line);
|
||||||
line = line + ch;
|
line = line + ch;
|
||||||
if (ch == '\r' || ch == '\n') {
|
Serial.println(line);
|
||||||
Serial.println(line);
|
if (liveData->bleConnected) {
|
||||||
liveData->pRemoteCharacteristicWrite->writeValue(line.c_str(), line.length());
|
liveData->pRemoteCharacteristicWrite->writeValue(line.c_str(), line.length());
|
||||||
line = "";
|
|
||||||
}
|
}
|
||||||
}
|
line = "";
|
||||||
|
} else {
|
||||||
// Can send next command from queue to OBD
|
line = line + ch;
|
||||||
if (liveData->canSendNextAtCommand) {
|
|
||||||
liveData->canSendNextAtCommand = false;
|
|
||||||
doNextAtCommand();
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Can send next command from queue to OBD
|
||||||
|
if (liveData->canSendNextAtCommand) {
|
||||||
|
liveData->canSendNextAtCommand = false;
|
||||||
|
doNextAtCommand();
|
||||||
|
}
|
||||||
|
|
||||||
#ifdef SIM800L_ENABLED
|
#ifdef SIM800L_ENABLED
|
||||||
if(liveData->params.lastDataSent + SIM800L_TIMER < liveData->params.currentTime && liveData->params.sim800l_enabled) {
|
if (liveData->params.lastDataSent + SIM800L_TIMER < liveData->params.currentTime && liveData->params.sim800l_enabled) {
|
||||||
sendDataViaGPRS();
|
sendDataViaGPRS();
|
||||||
liveData->params.lastDataSent = liveData->params.currentTime;
|
liveData->params.lastDataSent = liveData->params.currentTime;
|
||||||
}
|
}
|
||||||
#endif // SIM800L_ENABLED
|
#endif // SIM800L_ENABLED
|
||||||
|
|
||||||
board->mainLoop();
|
board->mainLoop();
|
||||||
|
|
||||||
// currentTime & 1ms delay
|
|
||||||
struct tm now;
|
|
||||||
getLocalTime(&now, 0);
|
|
||||||
liveData->params.currentTime = mktime(&now);
|
|
||||||
// Shutdown when car is off
|
|
||||||
if (liveData->params.automaticShutdownTimer != 0 && liveData->params.currentTime - liveData->params.automaticShutdownTimer > 5)
|
|
||||||
board->shutdownDevice();
|
|
||||||
if (board->scanDevices) {
|
if (board->scanDevices) {
|
||||||
board->scanDevices = false;
|
board->scanDevices = false;
|
||||||
startBleScan();
|
startBleScan();
|
||||||
|
|||||||
25
flash_linux.sh
Normal file
25
flash_linux.sh
Normal file
@@ -0,0 +1,25 @@
|
|||||||
|
#!/bin/bash
|
||||||
|
|
||||||
|
# Setup
|
||||||
|
# 1. Ensure you have Python 2.7 or 3.4+ installed
|
||||||
|
# 2. `pip install esptool`
|
||||||
|
# 3. `sudo usermod -a -G dialout <USERNAME>` // log out and log in is required
|
||||||
|
|
||||||
|
# Select distribution:
|
||||||
|
# TTGO T4
|
||||||
|
DIST=./dist/ttgo_t4_v13
|
||||||
|
|
||||||
|
# or m5stack
|
||||||
|
DIST=./dist/m5stack_core1
|
||||||
|
|
||||||
|
# Set USB port
|
||||||
|
PORT=/dev/ttyUSB0
|
||||||
|
|
||||||
|
esptool.py -p $PORT -b 921600 write_flash \
|
||||||
|
--flash_mode dio \
|
||||||
|
--flash_size detect \
|
||||||
|
--flash_freq 80m \
|
||||||
|
0xe000 $DIST/boot_app0.bin \
|
||||||
|
0x1000 $DIST/bootloader_qio_80m.bin \
|
||||||
|
0x10000 $DIST/evDash.ino.bin \
|
||||||
|
0x8000 $DIST/evDash.ino.partitions.bin
|
||||||
98
menu.h
98
menu.h
@@ -2,16 +2,16 @@
|
|||||||
|
|
||||||
#include "config.h";
|
#include "config.h";
|
||||||
|
|
||||||
MENU_ITEM menuItemsSource[78] = {
|
MENU_ITEM menuItemsSource[100] = {
|
||||||
|
|
||||||
{0, 0, 0, "<- exit menu"},
|
{0, 0, 0, "<- exit menu"},
|
||||||
{1, 0, -1, "Vehicle type"},
|
{MENU_VEHICLE_TYPE, 0, -1, "Vehicle type"},
|
||||||
{2, 0, -1, "Select OBD2BLE adapter"},
|
{2, 0, -1, "Select OBD2 BLE4 adapter"},
|
||||||
{3, 0, -1, "Others"},
|
{3, 0, -1, "Others"},
|
||||||
{4, 0, -1, "Units"},
|
{4, 0, -1, "Units"},
|
||||||
{8, 0, -1, "Factory reset"},
|
{8, 0, -1, "Factory reset"},
|
||||||
{9, 0, -1, "Save settings"},
|
{MENU_SAVE_SETTINGS, 0, -1, "Save settings"},
|
||||||
{10, 0, -1, "Version"},
|
{MENU_APP_VERSION, 0, -1, "Version"},
|
||||||
{11, 0, -1, "Shutdown"},
|
{11, 0, -1, "Shutdown"},
|
||||||
|
|
||||||
{100, 1, 0, "<- parent menu"},
|
{100, 1, 0, "<- parent menu"},
|
||||||
@@ -20,59 +20,59 @@ MENU_ITEM menuItemsSource[78] = {
|
|||||||
{103, 1, -1, "Hyundai Ioniq 2018 28kWh"},
|
{103, 1, -1, "Hyundai Ioniq 2018 28kWh"},
|
||||||
{104, 1, -1, "Kia eNiro 2020 39kWh"},
|
{104, 1, -1, "Kia eNiro 2020 39kWh"},
|
||||||
{105, 1, -1, "Hyundai Kona 2020 39kWh"},
|
{105, 1, -1, "Hyundai Kona 2020 39kWh"},
|
||||||
//{106, 1, -1, "Renault Zoe 22kWh (DEV)"},
|
{106, 1, -1, "Renault Zoe 22kWh (DEV)"},
|
||||||
{107, 1, -1, "Debug OBD2 Kia"},
|
{107, 1, -1, "Kia Niro PHEV 8.9kWh"},
|
||||||
|
{120, 1, -1, "Debug OBD2 Kia"},
|
||||||
|
|
||||||
{300, 3, 0, "<- parent menu"},
|
{300, 3, 0, "<- parent menu"},
|
||||||
{301, 3, -1, "Screen rotation"},
|
// {MENU_WIFI, 3, -1, "[dev] WiFi network"},
|
||||||
{302, 3, -1, "Default screen"},
|
{MENU_SDCARD, 3, -1, "SD card"},
|
||||||
{303, 3, -1, "Debug screen off/on"},
|
{MENU_GPS, 3, -1, "GPS"},
|
||||||
{304, 3, -1, "LCD brightness"},
|
{MENU_GPRS, 3, -1, "[dev] GSM/GPRS"},
|
||||||
{305, 3, -1, "Pre-drawn ch.graphs 0/1"},
|
//{MENU_REMOTE_UPLOAD, 3, -1, "[dev] Remote upload"},
|
||||||
{306, 3, -1, "[DEV] WiFi network"},
|
//{MENU_NTP, 3, -1, "[dev] NTP"},
|
||||||
{307, 3, -1, "[DEV] SD card"},
|
{MENU_SCREEN_ROTATION, 3, -1, "Screen rotation"},
|
||||||
|
{MENU_DEFAULT_SCREEN, 3, -1, "Default screen"},
|
||||||
|
{MENU_SCREEN_BRIGHTNESS, 3, -1, "LCD brightness"},
|
||||||
|
{MENU_PREDRAWN_GRAPHS, 3, -1, "Pre-drawn ch.graphs"},
|
||||||
|
{MENU_HEADLIGHTS_REMINDER, 3, -1, "Headlight reminder"},
|
||||||
|
{MENU_DEBUG_SCREEN, 3, -1, "Debug screen"},
|
||||||
|
|
||||||
|
/*
|
||||||
|
// NTP
|
||||||
|
byte ntpEnabled; // 0/1
|
||||||
|
byte ntpTimezone;
|
||||||
|
byte ntpDaySaveTime; // 0/1
|
||||||
|
// GPRS SIM800L
|
||||||
|
byte gprsEnabled; // 0/1
|
||||||
|
char gprsApn[64];
|
||||||
|
// Remote upload
|
||||||
|
byte remoteUploadEnabled; // 0/1
|
||||||
|
char remoteApiUrl[64];
|
||||||
|
char remoteApiKey[32];*/
|
||||||
|
|
||||||
{400, 4, 0, "<- parent menu"},
|
{400, 4, 0, "<- parent menu"},
|
||||||
{401, 4, -1, "Distance"},
|
{MENU_DISTANCE_UNIT, 4, -1, "Distance"},
|
||||||
{402, 4, -1, "Temperature"},
|
{MENU_TEMPERATURE_UNIT, 4, -1, "Temperature"},
|
||||||
{403, 4, -1, "Pressure"},
|
{MENU_PRESSURE_UNIT, 4, -1, "Pressure"},
|
||||||
|
|
||||||
{3010, 301, 3, "<- parent menu"},
|
{3010, 301, 3, "<- parent menu"},
|
||||||
{3011, 301, -1, "Normal"},
|
{MENU_WIFI_ENABLED, 301, -1, "WiFi enabled"},
|
||||||
{3012, 301, -1, "Flip vertical"},
|
{MENU_WIFI_SSID, 301, -1, "SSID"},
|
||||||
|
{MENU_WIFI_PASSWORD, 301, -1, "Password"},
|
||||||
{3020, 302, 3, "<- parent menu"},
|
|
||||||
{3021, 302, -1, "Auto mode"},
|
|
||||||
{3022, 302, -1, "Basic info"},
|
|
||||||
{3023, 302, -1, "Speed"},
|
|
||||||
{3024, 302, -1, "Battery cells"},
|
|
||||||
{3025, 302, -1, "Charging graph"},
|
|
||||||
|
|
||||||
{3030, 303, 3, "<- parent menu"},
|
|
||||||
{3031, 303, -1, "Off"},
|
|
||||||
{3032, 303, -1, "On"},
|
|
||||||
|
|
||||||
{3040, 304, 3, "<- parent menu"},
|
{3040, 304, 3, "<- parent menu"},
|
||||||
{3041, 304, -1, "Auto"},
|
{MENU_SDCARD_ENABLED, 304, -1, "SD enabled"},
|
||||||
{3042, 304, -1, "20%"},
|
{MENU_SDCARD_AUTOSTARTLOG, 304, -1, "Autostart log enabled"},
|
||||||
{3043, 304, -1, "50%"},
|
{MENU_SDCARD_MOUNT_STATUS, 304, -1, "Status"},
|
||||||
{3044, 304, -1, "100%"},
|
{MENU_SDCARD_REC, 304, -1, "Record"},
|
||||||
|
|
||||||
{3050, 305, 3, "<- parent menu"},
|
|
||||||
{3051, 305, -1, "Off"},
|
|
||||||
{3052, 305, -1, "On"},
|
|
||||||
|
|
||||||
{3060, 306, 3, "<- parent menu"},
|
{3060, 306, 3, "<- parent menu"},
|
||||||
{3061, 306, -1, "WiFi off/on"},
|
{3061, 306, -1, "Auto mode"},
|
||||||
{3062, 306, -1, "SSID"},
|
{3062, 306, -1, "Basic info"},
|
||||||
{3063, 306, -1, "Password"},
|
{3063, 306, -1, "Speed"},
|
||||||
|
{3064, 306, -1, "Battery cells"},
|
||||||
{3070, 307, 3, "<- parent menu"},
|
{3065, 306, -1, "Charging graph"},
|
||||||
{3071, 307, -1, "Info:"},
|
|
||||||
{3072, 307, -1, "Mount manually"},
|
|
||||||
{3073, 307, -1, "Record now"},
|
|
||||||
{3074, 307, -1, "Stop recording"},
|
|
||||||
{3075, 307, -1, "Record on boot off/on"},
|
|
||||||
|
|
||||||
{4010, 401, 4, "<- parent menu"},
|
{4010, 401, 4, "<- parent menu"},
|
||||||
{4011, 401, -1, "Kilometers"},
|
{4011, 401, -1, "Kilometers"},
|
||||||
|
|||||||
Reference in New Issue
Block a user