diff --git a/.cproject b/.cproject
index 541a2bd..101aa62 100644
--- a/.cproject
+++ b/.cproject
@@ -1,53 +1,63 @@
-
-
+
+
+
+
-
-
-
-
-
-
-
-
-
@@ -55,11 +65,12 @@
-
+
+
-
+
\ No newline at end of file
diff --git a/.gitignore b/.gitignore
index e570238..752b375 100644
--- a/.gitignore
+++ b/.gitignore
@@ -2,6 +2,8 @@
bin/
bin-debug/
bin-release/
+.ino.cpp
+website/minified
# Other files and folders
.settings/
@@ -21,3 +23,4 @@ Release
*.map
*.srec
*.vcx*
+/sloeber.ino.cpp
diff --git a/.project.copy b/.project.copy
deleted file mode 100644
index 25abf59..0000000
--- a/.project.copy
+++ /dev/null
@@ -1,74 +0,0 @@
-
-
- GEVCU
-
-
-
-
-
- org.eclipse.cdt.managedbuilder.core.genmakebuilder
- clean,full,incremental,
-
-
-
-
- org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder
- full,incremental,
-
-
-
-
-
- org.eclipse.cdt.core.cnature
- org.eclipse.cdt.core.ccnature
- org.eclipse.cdt.managedbuilder.core.managedBuildNature
- org.eclipse.cdt.managedbuilder.core.ScannerConfigNature
- it.baeyens.arduinonature
-
-
-
- Libraries/DueTimer
- 2
- ArduinoPivateLibPath/DueTimer
-
-
- Libraries/due_can
- 2
- ArduinoPivateLibPath/due_can
-
-
- Libraries/due_rtc
- 2
- ArduinoPivateLibPath/due_rtc
-
-
- Libraries/due_wire
- 2
- ArduinoPivateLibPath/due_wire
-
-
- arduino/core
- 2
- ArduinoPlatformPath/cores/arduino
-
-
- arduino/variant
- 2
- ArduinoPinPath/arduino_due_x
-
-
-
-
- ArduinoHardwareLibPath
- file:/Z:/development/arduino/arduino-1.5.2_win_32bit/hardware/arduino/sam/libraries
-
-
- ArduinoPinPath
- file:/Z:/development/arduino/arduino-1.5.2_win_32bit/hardware/arduino/sam/variants
-
-
- ArduinoPlatformPath
- file:/Z:/development/arduino/arduino-1.5.2_win_32bit/hardware/arduino/sam
-
-
-
diff --git a/.sproject b/.sproject
new file mode 100644
index 0000000..eda1e40
--- /dev/null
+++ b/.sproject
@@ -0,0 +1,15 @@
+Config.Release.board.BOARD.ID=arduino_due_x
+Config.Release.board.BOARD.TXT=${SLOEBER_HOME}/arduinoPlugin/packages/arduino/hardware/sam/1.6.12/boards.txt
+Config.Release.board.PROGRAMMER.NAME=Default
+Config.Release.board.UPLOAD.PORT=/dev/cu.usbmodem14101
+Config.Release.compile.sloeber.extra.all=
+Config.Release.compile.sloeber.extra.archive=
+Config.Release.compile.sloeber.extra.assembly=
+Config.Release.compile.sloeber.extra.c.compile=
+Config.Release.compile.sloeber.extra.compile=
+Config.Release.compile.sloeber.extra.cpp.compile=
+Config.Release.compile.sloeber.extra.link=
+Config.Release.compile.sloeber.size.switch=false
+Config.Release.compile.sloeber.warning_level=ALL
+Config.Release.compile.sloeber.warning_level.custom=
+Config.Release.other.IS_VERSION_CONTROLLED=false
diff --git a/Base64.cpp b/Base64.cpp
new file mode 100644
index 0000000..2b03f96
--- /dev/null
+++ b/Base64.cpp
@@ -0,0 +1,136 @@
+#include "Base64.h"
+
+const char b64_alphabet[] = "ABCDEFGHIJKLMNOPQRSTUVWXYZ"
+ "abcdefghijklmnopqrstuvwxyz"
+ "0123456789+/";
+
+/* 'Private' declarations */
+inline void a3_to_a4(unsigned char * a4, unsigned char * a3);
+//inline void a4_to_a3(unsigned char * a3, unsigned char * a4);
+//inline unsigned char b64_lookup(char c);
+
+int base64_encode(char *output, char *input, int inputLen) {
+ int i = 0, j = 0;
+ int encLen = 0;
+ unsigned char a3[3];
+ unsigned char a4[4];
+
+ while(inputLen--) {
+ a3[i++] = *(input++);
+ if(i == 3) {
+ a3_to_a4(a4, a3);
+
+ for(i = 0; i < 4; i++) {
+ output[encLen++] = b64_alphabet[a4[i]];
+ }
+
+ i = 0;
+ }
+ }
+
+ if(i) {
+ for(j = i; j < 3; j++) {
+ a3[j] = '\0';
+ }
+
+ a3_to_a4(a4, a3);
+
+ for(j = 0; j < i + 1; j++) {
+ output[encLen++] = b64_alphabet[a4[j]];
+ }
+
+ while((i++ < 3)) {
+ output[encLen++] = '=';
+ }
+ }
+ output[encLen] = '\0';
+ return encLen;
+}
+
+/* not needed yet.. commented out in order not to bloat the binary
+int base64_decode(char * output, char * input, int inputLen) {
+ int i = 0, j = 0;
+ int decLen = 0;
+ unsigned char a3[3];
+ unsigned char a4[4];
+
+
+ while (inputLen--) {
+ if(*input == '=') {
+ break;
+ }
+
+ a4[i++] = *(input++);
+ if (i == 4) {
+ for (i = 0; i <4; i++) {
+ a4[i] = b64_lookup(a4[i]);
+ }
+
+ a4_to_a3(a3,a4);
+
+ for (i = 0; i < 3; i++) {
+ output[decLen++] = a3[i];
+ }
+ i = 0;
+ }
+ }
+
+ if (i) {
+ for (j = i; j < 4; j++) {
+ a4[j] = '\0';
+ }
+
+ for (j = 0; j <4; j++) {
+ a4[j] = b64_lookup(a4[j]);
+ }
+
+ a4_to_a3(a3,a4);
+
+ for (j = 0; j < i - 1; j++) {
+ output[decLen++] = a3[j];
+ }
+ }
+ output[decLen] = '\0';
+ return decLen;
+}
+
+int base64_enc_len(int plainLen) {
+ int n = plainLen;
+ return (n + 2 - ((n + 2) % 3)) / 3 * 4;
+}
+
+int base64_dec_len(char * input, int inputLen) {
+ int i = 0;
+ int numEq = 0;
+ for(i = inputLen - 1; input[i] == '='; i--) {
+ numEq++;
+ }
+
+ return ((6 * inputLen) / 8) - numEq;
+}
+*/
+inline void a3_to_a4(unsigned char * a4, unsigned char * a3) {
+ a4[0] = (a3[0] & 0xfc) >> 2;
+ a4[1] = ((a3[0] & 0x03) << 4) + ((a3[1] & 0xf0) >> 4);
+ a4[2] = ((a3[1] & 0x0f) << 2) + ((a3[2] & 0xc0) >> 6);
+ a4[3] = (a3[2] & 0x3f);
+}
+/*
+inline void a4_to_a3(unsigned char * a3, unsigned char * a4) {
+ a3[0] = (a4[0] << 2) + ((a4[1] & 0x30) >> 4);
+ a3[1] = ((a4[1] & 0xf) << 4) + ((a4[2] & 0x3c) >> 2);
+ a3[2] = ((a4[2] & 0x3) << 6) + a4[3];
+}
+
+inline unsigned char b64_lookup(char c) {
+ int i;
+ for(i = 0; i < 64; i++) {
+ if(b64_alphabet[i] == c) {
+ return i;
+ }
+ }
+
+ return -1;
+}
+*/
+
diff --git a/Base64.h b/Base64.h
new file mode 100644
index 0000000..cd17c53
--- /dev/null
+++ b/Base64.h
@@ -0,0 +1,75 @@
+#ifndef _BASE64_H
+#define _BASE64_H
+
+/* b64_alphabet:
+ * Description: Base64 alphabet table, a mapping between integers
+ * and base64 digits
+ * Notes: This is an extern here but is defined in Base64.c
+ */
+extern const char b64_alphabet[];
+
+/* base64_encode:
+ * Description:
+ * Encode a string of characters as base64
+ * Parameters:
+ * output: the output buffer for the encoding, stores the encoded string
+ * input: the input buffer for the encoding, stores the binary to be encoded
+ * inputLen: the length of the input buffer, in bytes
+ * Return value:
+ * Returns the length of the encoded string
+ * Requirements:
+ * 1. output must not be null or empty
+ * 2. input must not be null
+ * 3. inputLen must be greater than or equal to 0
+ */
+int base64_encode(char *output, char *input, int inputLen);
+
+/* base64_decode:
+ * Description:
+ * Decode a base64 encoded string into bytes
+ * Parameters:
+ * output: the output buffer for the decoding,
+ * stores the decoded binary
+ * input: the input buffer for the decoding,
+ * stores the base64 string to be decoded
+ * inputLen: the length of the input buffer, in bytes
+ * Return value:
+ * Returns the length of the decoded string
+ * Requirements:
+ * 1. output must not be null or empty
+ * 2. input must not be null
+ * 3. inputLen must be greater than or equal to 0
+ */
+int base64_decode(char *output, char *input, int inputLen);
+
+/* base64_enc_len:
+ * Description:
+ * Returns the length of a base64 encoded string whose decoded
+ * form is inputLen bytes long
+ * Parameters:
+ * inputLen: the length of the decoded string
+ * Return value:
+ * The length of a base64 encoded string whose decoded form
+ * is inputLen bytes long
+ * Requirements:
+ * None
+ */
+int base64_enc_len(int inputLen);
+
+/* base64_dec_len:
+ * Description:
+ * Returns the length of the decoded form of a
+ * base64 encoded string
+ * Parameters:
+ * input: the base64 encoded string to be measured
+ * inputLen: the length of the base64 encoded string
+ * Return value:
+ * Returns the length of the decoded form of a
+ * base64 encoded string
+ * Requirements:
+ * 1. input must not be null
+ * 2. input must be greater than or equal to zero
+ */
+int base64_dec_len(char *input, int inputLen);
+
+#endif // _BASE64_H
diff --git a/BatteryManager.cpp b/BatteryManager.cpp
index 7894f34..d5bc4d5 100644
--- a/BatteryManager.cpp
+++ b/BatteryManager.cpp
@@ -3,70 +3,285 @@
*
* Parent class for all battery management/monitoring systems
*
-Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
+ Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
-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:
+ 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 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.
+ 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 "BatteryManager.h"
-
-BatteryManager::BatteryManager() : Device()
+
+BatteryManager::BatteryManager() :
+ Device()
+{
+ packVoltage = 0;
+ packCurrent = 0;
+ soc = 0;
+ packAmphours = 0;
+ allowCharge = allowDischarge = false;
+ chargeLimit = dischargeLimit = 0;
+ systemTemperature = 0;
+ lowestCellTemp = highestCellTemp = 0;
+ lowestCellTempId = highestCellTempId = ID_UNKNOWN;
+ lowestCellVolts = highestCellVolts = averageCellVolts = 0;
+ lowestCellVoltsId = highestCellVoltsId = ID_UNKNOWN;
+ lowestCellResistance = highestCellResistance = averageCellResistance = 0;
+ lowestCellResistanceId = highestCellResistanceId = ID_UNKNOWN;
+ packHealth = 0;
+ packCycles = packResistance = 0;
+ chargerEnabled = false;
+}
+
+void BatteryManager::setup()
+{
+ Device::setup();
+
+}
+
+void BatteryManager::tearDown()
+{
+ Device::tearDown();
+
+ allowCharge = false;
+ allowDischarge = false;
+ chargeLimit = 0;
+ dischargeLimit = 0;
+ chargerEnabled = false;
+}
+
+DeviceType BatteryManager::getType()
+{
+ return DEVICE_BMS;
+}
+
+void BatteryManager::handleTick()
+{
+}
+
+bool BatteryManager::hasPackVoltage()
+{
+ return false;
+}
+
+bool BatteryManager::hasPackCurrent()
+{
+ return false;
+}
+
+bool BatteryManager::hasSoc()
+{
+ return false;
+}
+
+bool BatteryManager::hasAmpHours()
+{
+ return false;
+}
+
+bool BatteryManager::hasChargeLimit()
+{
+ return false;
+}
+
+bool BatteryManager::hasDischargeLimit()
+{
+ return false;
+}
+
+bool BatteryManager::hasAllowCharging()
+{
+ return false;
+}
+
+bool BatteryManager::hasAllowDischarging()
+{
+ return false;
+}
+
+bool BatteryManager::hasCellTemperatures()
+{
+ return false;
+}
+
+
+bool BatteryManager::hasCellVoltages()
+{
+ return false;
+}
+
+bool BatteryManager::hasCellResistance()
+{
+ return false;
+}
+
+bool BatteryManager::hasPackHealth()
+{
+ return false;
+}
+
+bool BatteryManager::hasPackCycles()
+{
+ return false;
+}
+
+bool BatteryManager::hasPackResistance()
+{
+ return false;
+}
+
+bool BatteryManager::hasChargerEnabled()
+{
+ return false;
+}
+
+uint16_t BatteryManager::getPackVoltage()
+{
+ return packVoltage;
+}
+
+int16_t BatteryManager::getPackCurrent()
+{
+ return packCurrent;
+}
+
+uint8_t BatteryManager::getSoc()
+{
+ return soc;
+}
+
+uint16_t BatteryManager::getAmpHours()
+{
+ return packAmphours;
+}
+
+uint16_t BatteryManager::getDischargeLimit()
+{
+ return dischargeLimit;
+}
+
+uint16_t BatteryManager::getChargeLimit()
+{
+ return chargeLimit;
+}
+
+bool BatteryManager::isChargeAllowed()
+{
+ return allowCharge;
+}
+
+bool BatteryManager::isDischargeAllowed()
+{
+ return allowDischarge;
+}
+
+int16_t BatteryManager::getLowestCellTemp()
+{
+ return lowestCellTemp;
+}
+
+int16_t BatteryManager::getHighestCellTemp()
+{
+ return highestCellTemp;
+}
+
+uint16_t BatteryManager::getLowestCellVolts()
+{
+ return lowestCellVolts;
+}
+
+uint16_t BatteryManager::getHighestCellVolts()
{
- packVoltage = 0;
- packCurrent = 0;
+ return highestCellVolts;
}
-BatteryManager::~BatteryManager()
+uint16_t BatteryManager::getAverageCellVolts()
{
+ return averageCellVolts;
}
-DeviceType BatteryManager::getType() {
- return (DEVICE_BMS);
+uint16_t BatteryManager::getLowestCellResistance()
+{
+ return lowestCellResistance;
+}
+
+uint16_t BatteryManager::getHighestCellResistance()
+{
+ return highestCellResistance;
}
-void BatteryManager::handleTick() {
+uint16_t BatteryManager::getAverageCellResistance()
+{
+ return averageCellVolts;
}
-void BatteryManager::setup() {
-#ifndef USE_HARD_CODED
- if (prefsHandler->checksumValid()) { //checksum is good, read in the values stored in EEPROM
- }
- else { //checksum invalid. Reinitialize values and store to EEPROM
- //prefsHandler->saveChecksum();
- }
-#else
-#endif
+uint8_t BatteryManager::getLowestCellTempId()
+{
+ return lowestCellTempId;
+}
-//TickHandler::getInstance()->detach(this);
-//TickHandler::getInstance()->attach(this, CFG_TICK_INTERVAL_MOTOR_CONTROLLER_DMOC);
+uint8_t BatteryManager::getHighestCellTempId()
+{
+ return highestCellTempId;
+}
+uint8_t BatteryManager::getLowestCellVoltsId()
+{
+ return lowestCellVoltsId;
}
-int BatteryManager::getPackVoltage()
+uint8_t BatteryManager::getHighestCellVoltsId()
{
- return packVoltage;
+ return highestCellVoltsId;
}
-signed int BatteryManager::getPackCurrent()
+uint8_t BatteryManager::getLowestCellResistanceId()
{
- return packCurrent;
+ return lowestCellResistanceId;
}
+uint8_t BatteryManager::getHighestCellResistanceId()
+{
+ return highestCellResistanceId;
+}
+
+uint8_t BatteryManager::getPackHealth()
+{
+ return packHealth;
+}
+
+uint16_t BatteryManager::getPackCycles()
+{
+ return packCycles;
+}
+
+uint16_t BatteryManager::getPackResistance()
+{
+ return packResistance;
+}
+
+uint8_t BatteryManager::getSystemTemperature()
+{
+ return systemTemperature;
+}
+
+bool BatteryManager::isChargerEnabled()
+{
+ return chargerEnabled;
+}
diff --git a/BatteryManager.h b/BatteryManager.h
index ec97268..2ca17a8 100644
--- a/BatteryManager.h
+++ b/BatteryManager.h
@@ -24,8 +24,8 @@ 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 BATTMANAGE_H_
#define BATTMANAGE_H_
@@ -33,35 +33,79 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
#include "config.h"
#include "Device.h"
-class BatteryManager : public Device {
+#define ID_UNKNOWN 255
+
+class BatteryManager : public Device
+{
public:
- BatteryManager();
- ~BatteryManager();
- int getPackVoltage(); //in tenths of a volt
- signed int getPackCurrent(); //in tenths of an amp
- //bool allowCharging();
- //bool allowDischarging();
- DeviceType getType();
+ BatteryManager();
void setup();
+ void tearDown();
+ DeviceType getType();
void handleTick();
- //a bunch of boolean functions. Derived classes must implment
- //these functions to tell everyone else what they support
- virtual bool hasPackVoltage() = 0;
- virtual bool hasPackCurrent() = 0;
- virtual bool hasTemperatures() = 0;
- virtual bool isChargeOK() = 0;
- virtual bool isDischargeOK() = 0;
-protected:
- int packVoltage; //tenths of a volt
- signed int packCurrent; //tenths of an amp
- int SOC; //state of charge in percent
- int lowestCellV, highestCellV; //in mv
- int lowestCellTemp, highestCellTemp;
- //should be some form of discharge and charge limit. I don't know if it should be % or amps
- //some BMS systems will report one way and some the other.
- int dischargeLimit, chargeLimit;
- bool allowCharge, allowDischarge;
+ //Derived classes must implment these functions to tell what they support
+ virtual bool hasPackVoltage();
+ virtual bool hasPackCurrent();
+ virtual bool hasSoc();
+ virtual bool hasAmpHours();
+ virtual bool hasChargeLimit();
+ virtual bool hasDischargeLimit();
+ virtual bool hasAllowCharging();
+ virtual bool hasAllowDischarging();
+ virtual bool hasCellTemperatures();
+ virtual bool hasCellVoltages();
+ virtual bool hasCellResistance();
+ virtual bool hasPackHealth();
+ virtual bool hasPackCycles();
+ virtual bool hasPackResistance();
+ virtual bool hasChargerEnabled();
+ uint16_t getPackVoltage(); // in 0.1V
+ int16_t getPackCurrent(); // in 0.1A
+ uint8_t getSoc(); // in 0.5%
+ uint16_t getAmpHours(); // in 0.1Ah
+ uint16_t getDischargeLimit(); // in 1A
+ uint16_t getChargeLimit(); // in 1A
+ bool isChargeAllowed();
+ bool isDischargeAllowed();
+ bool isChargerEnabled();
+ int16_t getLowestCellTemp(); // in 0.1C
+ int16_t getHighestCellTemp(); // in 0.1C
+ uint16_t getLowestCellVolts(); // in mV
+ uint16_t getHighestCellVolts(); // in mV
+ uint16_t getAverageCellVolts(); // in 0.0001V
+ uint16_t getLowestCellResistance(); // in 0.01mOhm
+ uint16_t getHighestCellResistance(); // in 0.01mOhm
+ uint16_t getAverageCellResistance(); // in 0.01mOhm
+ uint8_t getLowestCellTempId();
+ uint8_t getHighestCellTempId();
+ uint8_t getLowestCellVoltsId();
+ uint8_t getHighestCellVoltsId();
+ uint8_t getLowestCellResistanceId();
+ uint8_t getHighestCellResistanceId();
+ uint8_t getPackHealth(); // in 1%
+ uint16_t getPackCycles();
+ uint16_t getPackResistance(); // in 1mOhm
+ uint8_t getSystemTemperature(); // in 1C
+
+protected:
+ uint16_t packVoltage; //tenths of a volt
+ int16_t packCurrent; //tenths of an amp
+ uint8_t soc; //state of charge in 0.5%
+ uint16_t packAmphours; // Ah of pack in 0.1Ah
+ uint16_t dischargeLimit, chargeLimit; // in 1A
+ bool allowCharge, allowDischarge;
+ int8_t systemTemperature; // in 1C
+ int16_t lowestCellTemp, highestCellTemp; // in 0.1C
+ uint8_t lowestCellTempId, highestCellTempId; // 0-254, 255=undefined
+ uint16_t lowestCellVolts, highestCellVolts, averageCellVolts; // in 0.0001V
+ uint8_t lowestCellVoltsId, highestCellVoltsId; // 0-254, 255=undefined
+ uint16_t lowestCellResistance, highestCellResistance, averageCellResistance; // in 0.01mOhm
+ uint8_t lowestCellResistanceId, highestCellResistanceId; // 0-254, 255=undefined
+ uint8_t packHealth; // pack health (1%)
+ uint16_t packCycles; // number of total pack cycles
+ uint16_t packResistance; // pack resistance (1 mOhm)
+ bool chargerEnabled; // flag if true the charger may be enabled/engaged, if false charger must shut-down
private:
};
diff --git a/BrusaBSC6.cpp b/BrusaBSC6.cpp
new file mode 100644
index 0000000..ff1480d
--- /dev/null
+++ b/BrusaBSC6.cpp
@@ -0,0 +1,339 @@
+/*
+ * BrusaBSC6.cpp
+ *
+ *
+ Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
+
+ 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 "BrusaBSC6.h"
+
+/*
+ * Constructor
+ */
+BrusaBSC6::BrusaBSC6() : DcDcConverter()
+{
+ prefsHandler = new PrefHandler(BRUSA_BSC6);
+ commonName = "Brusa BSC6 DC-DC Converter";
+
+ mode = 0;
+ lvCurrentAvailable = 0;
+ temperatureBuckBoostSwitch1 = 0;
+ temperatureBuckBoostSwitch2 = 0;
+ temperatureHvTrafostageSwitch1 = 0;
+ temperatureHvTrafostageSwitch2 = 0;
+ temperatureLvTrafostageSwitch1 = 0;
+ temperatureLvTrafostageSwitch2 = 0;
+ temperatureTransformerCoil1 = 0;
+ temperatureTransformerCoil2 = 0;
+ internal12VSupplyVoltage = 0;
+ lsActualVoltage = 0;
+ lsActualCurrent = 0;
+ lsCommandedCurrent = 0;
+ internalOperationState = 0;
+ bitfield = 0;
+}
+
+/**
+ * Tear down the controller in a safe way.
+ */
+void BrusaBSC6::tearDown()
+{
+ DcDcConverter::tearDown();
+ canHandlerEv.detach(this, BSC6_CAN_MASKED_ID, BSC6_CAN_MASK);
+ sendControl(); // as powerOn is false now, send last command to deactivate controller
+}
+
+void BrusaBSC6::handleStateChange(Status::SystemState oldState, Status::SystemState newState)
+{
+ bool powerOnBefore = powerOn;
+
+ DcDcConverter::handleStateChange(oldState, newState);
+
+ if (powerOnBefore != powerOn) {
+ if (powerOn) {
+ // register ourselves as observer of 0x26a-0x26f can frames
+ canHandlerEv.attach(this, BSC6_CAN_MASKED_ID, BSC6_CAN_MASK, false);
+ tickHandler.attach(this, CFG_TICK_INTERVAL_DCDC_BSC6);
+ } else {
+ tearDown();
+ }
+ }
+}
+
+/*
+ * Process event from the tick handler.
+ */
+void BrusaBSC6::handleTick()
+{
+ DcDcConverter::handleTick(); // call parent
+
+ sendControl();
+ sendLimits();
+}
+
+/*
+ * Send BSC6COM message to the DCDC converter.
+ *
+ * The message is used to set the operation mode, enable the converter
+ * and set the voltage limits.
+ */
+void BrusaBSC6::sendControl()
+{
+ BrusaBSC6Configuration *config = (BrusaBSC6Configuration *) getConfiguration();
+
+ outputFrameControl.data.bytes[0] =
+ ((ready || running) && powerOn ? enable : 0) |
+ (config->mode == 1 ? boostMode : 0) |
+ (config->debugMode ? debugMode : 0);
+
+ canHandlerEv.sendFrame(outputFrameControl);
+}
+
+/*
+ * Send BSC6LIM message to DCDC converter.
+ *
+ * This message controls the electrical limits in the converter.
+ */
+void BrusaBSC6::sendLimits()
+{
+ canHandlerEv.sendFrame(outputFrameLimits);
+}
+
+/*
+ * Processes an event from the CanHandler.
+ *
+ * In case a CAN message was received which pass the masking and id filtering,
+ * this method is called. Depending on the ID of the CAN message, the data of
+ * the incoming message is processed.
+ */
+void BrusaBSC6::handleCanFrame(CAN_FRAME *frame)
+{
+ switch (frame->id) {
+ case BSC6_CAN_ID_VALUES_1:
+ processValues1(frame->data.bytes);
+ break;
+ case BSC6_CAN_ID_VALUES_2:
+ processValues2(frame->data.bytes);
+ break;
+ case BSC6_CAN_ID_DEBUG_1:
+ processDebug1(frame->data.bytes);
+ break;
+ case BSC6_CAN_ID_DEBUG_2:
+ processDebug2(frame->data.bytes);
+ break;
+ }
+}
+
+/*
+ * Process a BSC6VAL1 message which was received from the converter.
+ *
+ * This message provides the general status of the converter as well as
+ * available high/low voltage current and voltage.
+ */
+void BrusaBSC6::processValues1(uint8_t data[])
+{
+ bitfield = (uint32_t)data[7] & 0x0F;
+
+ running = (bitfield & bsc6Running) ? true : false;
+ status.dcdcRunning = running;
+ ready = (bitfield & bsc6Ready) ? true : false;
+ if (bitfield & automatic) {
+ //TODO implement handling of automatic flag
+ }
+
+ hvVoltage = (uint16_t)(data[1] | (data[0] << 8));
+ lvVoltage = (uint8_t)data[2];
+ hvCurrent = (int16_t)(data[4] | (data[3] << 8)) - 250;
+ lvCurrent = (int16_t)(data[6] | (data[5] << 8)) - 280;
+ mode = (data[7] & 0xF0) >> 4;
+
+ if (logger.isDebug()) {
+ logger.debug(this, "status bitfield: %#08x, ready: %d, running: %d, HV: %fV %fA, LV: %fV %dA, mode %d", bitfield, ready, running, (float) hvVoltage / 10.0F, (float) hvCurrent / 10.0F, (float) lvVoltage / 10.0F, lvCurrent, mode);
+ }
+}
+
+/*
+ * Process a BSC6VAL2 message which was received from the converter.
+ *
+ * This message provides (critical) errors.
+ */
+void BrusaBSC6::processValues2(uint8_t data[])
+{
+ lvCurrentAvailable = (uint8_t)data[0];
+ temperature = (uint8_t)data[1] * 10;
+
+ bitfield = (uint32_t)((data[3] << 0) | (data[2] << 8) | (data[4] << 16));
+
+ if (bitfield != 0) {
+ String error;
+
+ appendMessage(error, bitfield, lowVoltageUndervoltage, "LV under-voltage");
+ appendMessage(error, bitfield, lowVoltageOvervoltage, "LV over-voltage");
+ appendMessage(error, bitfield, highVoltageUndervoltage, "HV under-voltage");
+ appendMessage(error, bitfield, highVoltageOvervoltage, "HV over-voltage");
+ appendMessage(error, bitfield, internalSupply, "internal supply");
+ appendMessage(error, bitfield, temperatureSensor, "temperature sensor");
+ appendMessage(error, bitfield, trafoStartup, "trafo startup");
+ appendMessage(error, bitfield, overTemperature, "over temperature");
+ appendMessage(error, bitfield, highVoltageFuse, "HV fuse");
+ appendMessage(error, bitfield, lowVoltageFuse, "LV fuse");
+ appendMessage(error, bitfield, currentSensorLowSide, "current sensor low side");
+ appendMessage(error, bitfield, currentDeviation, "current deviation");
+ appendMessage(error, bitfield, interLock, "interlock");
+ appendMessage(error, bitfield, internalSupply12V, "internal supply 12V");
+ appendMessage(error, bitfield, internalSupply6V, "internal supply 6V");
+ appendMessage(error, bitfield, voltageDeviation, "voltage deviation");
+ appendMessage(error, bitfield, invalidValue, "invalid value");
+ appendMessage(error, bitfield, commandMessageLost, "cmd msg lost");
+ appendMessage(error, bitfield, limitMessageLost, "limit msg lost");
+ appendMessage(error, bitfield, crcErrorNVSRAM, "CRC error NVSRAM");
+ appendMessage(error, bitfield, brokenTemperatureSensor, "broken temp sensor");
+
+ logger.error(this, "error (%#08x): %s", bitfield, error.c_str());
+ }
+ if (logger.isDebug()) {
+ logger.debug(this, "LV current avail: %dA, maximum Temperature: %.1fC", lvCurrentAvailable, (float) temperature / 10.0F);
+ }
+}
+
+/*
+ * Process a BSC6DBG1 message which was received from the converter.
+ *
+ * This message provides various temperature readings.
+ */
+void BrusaBSC6::processDebug1(uint8_t data[])
+{
+ temperatureBuckBoostSwitch1 = (uint8_t)data[0];
+ temperatureBuckBoostSwitch2 = (uint8_t)data[1];
+ temperatureHvTrafostageSwitch1 = (uint8_t)data[2];
+ temperatureHvTrafostageSwitch2 = (uint8_t)data[3];
+ temperatureLvTrafostageSwitch1 = (uint8_t)data[4];
+ temperatureLvTrafostageSwitch2 = (uint8_t)data[5];
+ temperatureTransformerCoil1 = (uint8_t)data[6];
+ temperatureTransformerCoil2 = (uint8_t)data[7];
+
+ if (logger.isDebug()) {
+ logger.debug(this, "Temp buck/boost switch 1: %d�C, switch 2: %d�C", temperatureBuckBoostSwitch1, temperatureBuckBoostSwitch2);
+ logger.debug(this, "Temp HV trafostage switch 1: %d�C, switch 2: %d�C", temperatureHvTrafostageSwitch1, temperatureHvTrafostageSwitch2);
+ logger.debug(this, "Temp LV trafostage switch 1: %d�C, switch 2: %d�C", temperatureLvTrafostageSwitch1, temperatureLvTrafostageSwitch2);
+ logger.debug(this, "Temp transformer coil 1: %d�C, coil 2: %d�C", temperatureTransformerCoil1, temperatureTransformerCoil2);
+ }
+}
+
+/*
+ * Process a BSC6DBG2 message which was received from the converter.
+ *
+ * This message provides various temperature readings.
+ */
+void BrusaBSC6::processDebug2(uint8_t data[])
+{
+ internal12VSupplyVoltage = (uint8_t)data[0];
+ lsActualVoltage = (uint8_t)data[1];
+ lsActualCurrent = (int16_t)data[2] - 6000;
+ lsCommandedCurrent = (int16_t)data[3] - 6000;
+ internalOperationState = (uint8_t)data[4];
+
+ if (logger.isDebug()) {
+ logger.debug(this, "internal 12V supply: %.1fV, LS actual voltage: %.1fV", (float) internal12VSupplyVoltage / 10.0F, (float) lsActualVoltage / 10.0F);
+ logger.debug(this, "LS actual current: %.2fA, LS commanded current: %.2fA", (float) internal12VSupplyVoltage / 200.0F, (float) lsActualVoltage / 200.0F);
+ logger.debug(this, "internal power state: %d", internalOperationState);
+ }
+}
+
+/**
+ * Prepare the content of the CAN frames sent to the BSC6 so they don't have to be filled in every tick cycle
+ */
+void BrusaBSC6::prepareCanMessages()
+{
+ BrusaBSC6Configuration *config = (BrusaBSC6Configuration *) getConfiguration();
+
+ canHandlerEv.prepareOutputFrame(&outputFrameControl, BSC6_CAN_ID_COMMAND);
+ outputFrameControl.data.bytes[1] = constrain(config->lowVoltageCommand, 80, 160); // 8-16V in 0.1V, offset = 0V
+ outputFrameControl.data.bytes[2] = constrain(config->highVoltageCommand - 170, 20, 255); // 190-425V in 1V, offset = 170V
+ outputFrameControl.length = 3;
+
+ canHandlerEv.prepareOutputFrame(&outputFrameLimits, BSC6_CAN_ID_LIMIT);
+ outputFrameLimits.data.bytes[0] = constrain(config->hvUndervoltageLimit - 170, 0, 255);
+ outputFrameLimits.data.bytes[1] = constrain(config->lvBuckModeCurrentLimit, 0, 250);
+ outputFrameLimits.data.bytes[2] = constrain(config->hvBuckModeCurrentLimit, 0, 250);
+ outputFrameLimits.data.bytes[3] = constrain(config->lvUndervoltageLimit, 0, 160);
+ outputFrameLimits.data.bytes[4] = constrain(config->lvBoostModeCurrentLinit, 0, 250);
+ outputFrameLimits.data.bytes[5] = constrain(config->hvBoostModeCurrentLimit, 0, 250);
+ outputFrameLimits.length = 6;
+}
+
+/*
+ * Return the device id of this device
+ */
+DeviceId BrusaBSC6::getId()
+{
+ return BRUSA_BSC6;
+}
+
+/*
+ * Load configuration data from EEPROM.
+ *
+ * If not available or the checksum is invalid, default values are chosen.
+ */
+void BrusaBSC6::loadConfiguration()
+{
+ BrusaBSC6Configuration *config = (BrusaBSC6Configuration *) getConfiguration();
+
+ if (!config) { // as lowest sub-class make sure we have a config object
+ config = new BrusaBSC6Configuration();
+ setConfiguration(config);
+ }
+
+ DcDcConverter::loadConfiguration(); // call parent
+
+#ifdef USE_HARD_CODED
+
+ if (false) {
+#else
+ if (prefsHandler->checksumValid()) { //checksum is good, read in the values stored in EEPROM
+#endif
+ uint8_t temp;
+ prefsHandler->read(EEDC_DEBUG_MODE, &temp);
+ config->debugMode = (temp != 0);
+ } else { //checksum invalid. Reinitialize values and store to EEPROM
+ config->debugMode = false; // no debug messages
+ saveConfiguration();
+ }
+ logger.info(this, "debug: %d", config->debugMode);
+
+ prepareCanMessages();
+}
+
+/*
+ * Store the current configuration parameters to EEPROM.
+ */
+void BrusaBSC6::saveConfiguration()
+{
+ BrusaBSC6Configuration *config = (BrusaBSC6Configuration *) getConfiguration();
+
+ DcDcConverter::saveConfiguration(); // call parent
+ prefsHandler->write(EEDC_DEBUG_MODE, (uint8_t) (config->debugMode ? 1 : 0));
+ prefsHandler->saveChecksum();
+
+ prepareCanMessages();
+}
diff --git a/BrusaBSC6.h b/BrusaBSC6.h
new file mode 100644
index 0000000..9c8f127
--- /dev/null
+++ b/BrusaBSC6.h
@@ -0,0 +1,147 @@
+/*
+ * BrusaBSC6.h
+ *
+ *
+Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
+
+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 BRUSABSC6_H_
+#define BRUSABSC6_H_
+
+#include
+#include "config.h"
+#include "Status.h"
+#include "SystemIO.h"
+#include "TickHandler.h"
+#include "DeviceManager.h"
+#include "DeviceTypes.h"
+#include "DcDcConverter.h"
+
+// CAN bus id's for frames sent to BSC6
+
+#define BSC6_CAN_ID_COMMAND 0x260 // send commands (BSC6COM)
+#define BSC6_CAN_ID_LIMIT 0x261 // send limitations (BSC6LIM)
+
+// CAN bus id's for frames received from BSC6
+
+#define BSC6_CAN_ID_VALUES_1 0x26a // receive actual values and status info (BSC6VAL1) 01001101010
+#define BSC6_CAN_ID_VALUES_2 0x26b // receive actual values and error codes (BSC6VAL2) 01001101011
+#define BSC6_CAN_ID_DEBUG_1 0X26e // receive debug information (BSC6DBG1) 01001101110
+#define BSC6_CAN_ID_DEBUG_2 0X26f // receive debug information (BSC6DBG2) 01001101111
+#define BSC6_CAN_MASK 0x7fa // mask for above id's 11111111010
+#define BSC6_CAN_MASKED_ID 0x26a // masked id for id's from 0x26a to 0x26f 01001101010
+
+class BrusaBSC6Configuration : public DcDcConverterConfiguration
+{
+public:
+ bool debugMode;
+};
+
+class BrusaBSC6: public DcDcConverter, CanObserver
+{
+public:
+ // Message id=0x26a, BSC6VAL1
+ // The value is composed of 1 byte : data[7]
+ enum BSC6_Status {
+ bsc6Running = 1 << 0, // 0x01, data[7], Motorola bit 63
+ bsc6Ready = 1 << 1, // 0x02, data[7], Motorola bit 62
+ automatic = 1 << 2 // 0x04, data[7], Motorola bit 61
+ };
+
+ // Message id=0x26b, BSC6VAL2
+ // The error value is composed of 3 bytes : (data[3] << 0) | (data[2] << 8) | (data[4] << 16)
+ enum BSC6_Error {
+ lowVoltageUndervoltage = 1 << 0, // 0x000001, data[3], Motorola bit 31
+ lowVoltageOvervoltage = 1 << 1, // 0x000002, data[3], Motorola bit 30
+ highVoltageUndervoltage = 1 << 2, // 0x000004, data[3], Motorola bit 29
+ highVoltageOvervoltage = 1 << 3, // 0x000008, data[3], Motorola bit 28
+ internalSupply = 1 << 4, // 0x000010, data[3], Motorola bit 27
+ temperatureSensor = 1 << 5, // 0x000020, data[3], Motorola bit 26
+ trafoStartup = 1 << 6, // 0x000040, data[3], Motorola bit 25
+ overTemperature = 1 << 7, // 0x000080, data[3], Motorola bit 24
+
+ highVoltageFuse = 1 << 8, // 0x000100, data[2], Motorola bit 23
+ lowVoltageFuse = 1 << 9, // 0x000200, data[2], Motorola bit 22
+ currentSensorLowSide = 1 << 10, // 0x000400, data[2], Motorola bit 21
+ currentDeviation = 1 << 11, // 0x000800, data[2], Motorola bit 20
+ interLock = 1 << 12, // 0x001000, data[2], Motorola bit 19
+ internalSupply12V = 1 << 13, // 0x002000, data[2], Motorola bit 18
+ internalSupply6V = 1 << 14, // 0x004000, data[2], Motorola bit 17
+ voltageDeviation = 1 << 15, // 0x008000, data[2], Motorola bit 16
+
+ invalidValue = 1 << 16, // 0x010000, data[4], Motorola bit 39
+ commandMessageLost = 1 << 17, // 0x020000, data[4], Motorola bit 38
+ limitMessageLost = 1 << 18, // 0x040000, data[4], Motorola bit 37
+ crcErrorNVSRAM = 1 << 22, // 0x400000, data[4], Motorola bit 33
+ brokenTemperatureSensor = 1 << 23, // 0x800000, data[4], Motorola bit 32
+ };
+
+ // Message id=0x260, BSC6COM
+ // The value is composed of 1 byte : data[0]
+ enum BSC6_Command {
+ enable = 1 << 0, // 0x01, data[0], Motorola bit 7
+ boostMode = 1 << 1, // 0x02, data[0], Motorola bit 6
+ debugMode = 1 << 7 // 0x80, data[0], Motorola bit 0
+ };
+
+ BrusaBSC6();
+ void handleStateChange(Status::SystemState, Status::SystemState);
+ void handleTick();
+ void handleCanFrame(CAN_FRAME *frame);
+ void tearDown();
+ DeviceId getId();
+
+ void loadConfiguration();
+ void saveConfiguration();
+
+private:
+ uint32_t bitfield; // various bit fields
+ uint8_t mode; // operation mode / status
+ uint8_t lvCurrentAvailable; // 0-250A in 1A
+ uint8_t temperatureBuckBoostSwitch1; // 0 - 180C in 1C
+ uint8_t temperatureBuckBoostSwitch2; // 0 - 180C in 1C
+ uint8_t temperatureHvTrafostageSwitch1; // 0 - 180C in 1C
+ uint8_t temperatureHvTrafostageSwitch2; // 0 - 180C in 1C
+ uint8_t temperatureLvTrafostageSwitch1; // 0 - 180C in 1C
+ uint8_t temperatureLvTrafostageSwitch2; // 0 - 180C in 1C
+ uint8_t temperatureTransformerCoil1; // 0 - 180C in 1C
+ uint8_t temperatureTransformerCoil2; // 0 - 180C in 1C
+ uint8_t internal12VSupplyVoltage; // 0 - 20V in 0.1V
+ uint8_t lsActualVoltage; // 0 - 25V in 0.1V
+ uint16_t lsActualCurrent; // -30 - 30A in 0.005A, offset = -30A
+ uint16_t lsCommandedCurrent; // -30 - 30A in 0.005A, offset = -30A
+ uint8_t internalOperationState;
+
+ CAN_FRAME outputFrameControl; // the output CAN frame for control message;
+ CAN_FRAME outputFrameLimits; // the output CAN frame for limit message;
+
+ void sendControl();
+ void sendLimits();
+ void processValues1(uint8_t data[]);
+ void processValues2(uint8_t data[]);
+ void processDebug1(uint8_t data[]);
+ void processDebug2(uint8_t data[]);
+ void prepareCanMessages();
+};
+
+#endif /* BRUSABSC6_H_ */
diff --git a/BrusaDMC5.cpp b/BrusaDMC5.cpp
new file mode 100644
index 0000000..5644566
--- /dev/null
+++ b/BrusaDMC5.cpp
@@ -0,0 +1,557 @@
+/*
+ * BrusaDMC5.cpp
+ *
+ *
+ Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
+
+ 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 "BrusaDMC5.h"
+
+/*
+ Warning:
+ At high speed disable the DMC_EnableRq can be dangerous because a field weakening current is
+ needed to achieve zero torque. Switching off the DMC in such a situation will make heavy regenerat-
+ ing torque that can't be controlled.
+ */
+
+/*
+ * Constructor
+ */
+BrusaDMC5::BrusaDMC5() : MotorController()
+{
+ prefsHandler = new PrefHandler(BRUSA_DMC5);
+ mechanicalPower = 0;
+ torqueAvailable = 0;
+ maxPositiveTorque = 0;
+ minNegativeTorque = 0;
+ limiterStateNumber = 0;
+ tickCounter = 0;
+ bitfield = 0;
+ canMessageLost = false;
+
+ commonName = "Brusa DMC5 Inverter";
+}
+
+/**
+ * Tear down the controller in a safe way.
+ */
+void BrusaDMC5::tearDown()
+{
+ MotorController::tearDown();
+
+ canHandlerEv.detach(this, DMC5_CAN_MASKED_ID, DMC5_CAN_MASK);
+
+ // for safety reasons at power off, first request 0 torque
+ // this allows the controller to dissipate residual fields first
+ sendControl();
+}
+
+/**
+ * act on messages the super-class does not react upon, like state change
+ * to ready or running which should enable/disable the controller
+ */
+void BrusaDMC5::handleStateChange(Status::SystemState oldState, Status::SystemState newState)
+{
+ MotorController::handleStateChange(oldState, newState);
+
+ // as the DMC is not sending/receiving messages as long as the enable signal is low
+ // (state != ready / running), attach to can/tick handler only when running.
+ if (newState == Status::running) {
+ // register ourselves as observer of 0x258-0x268 and 0x458 can frames
+ canHandlerEv.attach(this, DMC5_CAN_MASKED_ID, DMC5_CAN_MASK, false);
+ tickHandler.attach(this, CFG_TICK_INTERVAL_MOTOR_CONTROLLER_BRUSA);
+ } else {
+ if (oldState == Status::running) {
+ tearDown();
+ }
+ }
+}
+
+/*
+ * Process event from the tick handler.
+ *
+ * The super-class requests desired levels from the throttle and
+ * brake and decides which one to apply.
+ */
+void BrusaDMC5::handleTick()
+{
+ MotorController::handleTick(); // call parent
+
+ sendControl(); // send CTRL every 30ms (min 10ms, max 100ms)
+ sendControl2(); // send CTRL_2 every 30ms (min 10ms, max 100ms)
+ if (tickCounter++ > 10) {
+ sendLimits(); // send LIMIT every 11*30ms = 330ms (min 100ms, max 1000ms)
+ tickCounter = 0;
+ }
+}
+
+/*
+ * Send DMC_CTRL message to the motor controller.
+ *
+ * This message controls the power-stage in the controller, clears the error latch
+ * in case errors were detected and requests the desired torque / speed.
+ */
+void BrusaDMC5::sendControl()
+{
+ BrusaDMC5Configuration *config = (BrusaDMC5Configuration *) getConfiguration();
+
+ outputFrameControl.data.bytes[0] = 0;
+ if (canMessageLost) {
+ outputFrameControl.data.bytes[0] |= clearErrorLatch;
+ logger.warn(this, "clearing error latch");
+ canMessageLost = false;
+ }// else {
+
+ // to safe energy only enable the power-stage when positive acceleration is requested or the motor is still spinning (to control regen)
+ // see warning in Brusa docs about field weakening current to prevent uncontrollable regen
+ if (ready && ((getThrottleLevel() > 0 && powerOn) || (speedActual != 0))) {
+ outputFrameControl.data.bytes[0] |= enablePowerStage;
+ }
+
+ if (powerOn && ready) {
+ int16_t speedCommand = getSpeedRequested();
+ int16_t torqueCommand = getTorqueRequested();
+
+ outputFrameControl.data.bytes[0] |= (config->invertDirection ^ (getGear() == GEAR_REVERSE) ? enableNegativeTorqueSpeed : enablePositiveTorqueSpeed);
+
+ // prevent regen if BMS limits charge power to below 32A to prevent oscillation by current limiter
+ if (torqueCommand < 0 && speedActual < 2000) {
+ BatteryManager *batteryManager = deviceManager.getBatteryManager();
+ if (batteryManager && batteryManager->hasChargeLimit() && batteryManager->getChargeLimit() < 32) {
+ if (speedActual > 1500) {
+ torqueCommand = torqueCommand * (speedActual - 1500) / 500;
+ } else {
+ torqueCommand = 0;
+ }
+ }
+ }
+
+ if (config->powerMode == modeSpeed) {
+ outputFrameControl.data.bytes[0] |= enableSpeedMode;
+ if (config->invertDirection ^ (getGear() == GEAR_REVERSE)) { // reverse the motor direction if specified
+ speedCommand *= -1;
+ }
+ } else {
+ if (config->invertDirection ^ (getGear() == GEAR_REVERSE)) { // reverse the motor direction if specified
+ torqueCommand *= -1;
+ }
+ }
+ if (config->enableOscillationLimiter) {
+ outputFrameControl.data.bytes[0] |= enableOscillationLimiter;
+ }
+
+ speedCommand = constrain(speedCommand, -32760, 32760);
+ // set the speed in rpm, the values are constrained to prevent a fatal overflow
+ outputFrameControl.data.bytes[2] = (speedCommand & 0xFF00) >> 8;
+ outputFrameControl.data.bytes[3] = (speedCommand & 0x00FF);
+
+ torqueCommand = constrain(torqueCommand, -3275, 3275);
+ // set the torque in 0.01Nm (GEVCU uses 0.1Nm -> multiply by 10), the values are constrained to prevent a fatal overflow
+ outputFrameControl.data.bytes[4] = ((torqueCommand * 10) & 0xFF00) >> 8;
+ outputFrameControl.data.bytes[5] = ((torqueCommand * 10) & 0x00FF);
+ }
+// }
+ canHandlerEv.sendFrame(outputFrameControl);
+}
+
+/*
+ * Send DMC_CTRL2 message to the motor controller.
+ *
+ * This message controls the mechanical power limits for motor- and regen-mode.
+ */
+void BrusaDMC5::sendControl2()
+{
+ canHandlerEv.sendFrame(outputFrameControl2);
+}
+
+/*
+ * Send DMC_LIM message to the motor controller.
+ *
+ * This message controls the electrical limits in the controller.
+ */
+void BrusaDMC5::sendLimits()
+{
+ BrusaDMC5Configuration *config = (BrusaDMC5Configuration *) getConfiguration();
+ BatteryManager *batteryManager = deviceManager.getBatteryManager();
+
+ uint16_t currentLimitMotor = config->dcCurrentLimitMotor;
+ uint16_t currentLimitRegen = config->dcCurrentLimitRegen;
+
+ if (batteryManager) {
+ if (batteryManager->hasDischargeLimit()) {
+ currentLimitMotor = batteryManager->getDischargeLimit() * 10;
+ } else if (batteryManager->hasAllowDischarging() && !batteryManager->isDischargeAllowed()) {
+ currentLimitMotor = 0;
+ logger.info(this, "Motor power limited by BMS to 0");
+ }
+
+ if (batteryManager->hasChargeLimit()) {
+ currentLimitRegen = batteryManager->getChargeLimit() * 10;
+ } else if (batteryManager->hasAllowCharging() && !batteryManager->isChargeAllowed()) {
+ currentLimitRegen = 0;
+ }
+ }
+ currentLimitMotor = constrain(currentLimitMotor, 0, 65535);
+ currentLimitRegen = constrain(currentLimitRegen, 0, 65535);
+ outputFrameLimits.data.bytes[4] = (currentLimitMotor & 0xFF00) >> 8;
+ outputFrameLimits.data.bytes[5] = (currentLimitMotor & 0x00FF);
+ outputFrameLimits.data.bytes[6] = (currentLimitRegen & 0xFF00) >> 8;
+ outputFrameLimits.data.bytes[7] = (currentLimitRegen & 0x00FF);
+
+ canHandlerEv.sendFrame(outputFrameLimits);
+}
+
+/*
+ * Processes an event from the CanHandler.
+ *
+ * In case a CAN message was received which pass the masking and id filtering,
+ * this method is called. Depending on the ID of the CAN message, the data of
+ * the incoming message is processed.
+ */
+void BrusaDMC5::handleCanFrame(CAN_FRAME *frame)
+{
+ switch (frame->id) {
+ case DMC5_CAN_ID_STATUS:
+ processStatus(frame->data.bytes);
+ reportActivity();
+ break;
+ case DMC5_CAN_ID_ACTUAL_VALUES:
+ processActualValues(frame->data.bytes);
+ reportActivity();
+ break;
+ case DMC5_CAN_ID_ERRORS:
+ processErrors(frame->data.bytes);
+ reportActivity();
+ break;
+ case DMC5_CAN_ID_TORQUE_LIMIT:
+ processTorqueLimit(frame->data.bytes);
+ reportActivity();
+ break;
+ case DMC5_CAN_ID_TEMP:
+ processTemperature(frame->data.bytes);
+ reportActivity();
+ break;
+ }
+}
+
+/*
+ * Process a DMC_TRQS message which was received from the motor controller.
+ *
+ * This message provides the general status of the controller as well as
+ * available and current torque and speed.
+ */
+void BrusaDMC5::processStatus(uint8_t data[])
+{
+ BrusaDMC5Configuration *config = (BrusaDMC5Configuration *) getConfiguration();
+
+ bitfield = (uint32_t) (data[1] | (data[0] << 8));
+ torqueAvailable = (int16_t) (data[3] | (data[2] << 8)) / 10;
+ torqueActual = (int16_t) (data[5] | (data[4] << 8)) / 10;
+ speedActual = (int16_t) (data[7] | (data[6] << 8));
+
+ if (config->invertDirection ^ (getGear() == GEAR_REVERSE)) {
+ speedActual *= -1;
+ torqueActual *= -1;
+ }
+
+ if (bitfield & errorFlag) {
+ logger.error(this, "Error reported from motor controller!");
+// running = false;
+// ready = false;
+ }// else {
+ ready = (bitfield & dmc5Ready) ? true : false;
+ running = (bitfield & dmc5Running) ? true : false;
+// }
+
+ status.warning = (bitfield & warningFlag) ? true : false;
+ status.limitationTorque = (bitfield & torqueLimitation) ? true : false;
+ status.limitationMotorModel = (bitfield & motorModelLimitation) ? true : false;
+ status.limitationMechanicalPower = (bitfield & mechanicalPowerLimitation) ? true : false;
+ status.limitationMaxTorque = (bitfield & maxTorqueLimitation) ? true : false;
+ status.limitationAcCurrent = (bitfield & acCurrentLimitation) ? true : false;
+ status.limitationControllerTemperature = (bitfield & temperatureLimitation) ? true : false;
+ status.limitationSpeed = (bitfield & speedLimitation) ? true : false;
+ status.limitationDcVoltage = (bitfield & voltageLimitation) ? true : false;
+ status.limitationDcCurrent = (bitfield & currentLimitation) ? true : false;
+ status.limitationSlewRate = (bitfield & slewRateLimitation) ? true : false;
+ status.limitationMotorTemperature = (bitfield & motorTemperatureLimitation) ? true : false;
+
+ if (logger.isDebug()) {
+ logger.debug(this, "status: %#08x, ready: %d, running: %d, torque avail: %.2fNm, actual : %.2fNm, speed actual: %drpm", bitfield,
+ ready, running, torqueAvailable / 10.0F, torqueActual / 10.0F, speedActual);
+ }
+}
+
+/*
+ * Process a DMC_ACTV message which was received from the motor controller.
+ *
+ * This message provides information about current electrical conditions and
+ * applied mechanical power.
+ */
+void BrusaDMC5::processActualValues(uint8_t data[])
+{
+ dcVoltage = (uint16_t) (data[1] | (data[0] << 8));
+ dcCurrent = (int16_t) (data[3] | (data[2] << 8));
+ acCurrent = (uint16_t) (data[5] | (data[4] << 8)) / 2.5;
+ mechanicalPower = (int16_t) (data[7] | (data[6] << 8)) / 6.25;
+
+ if (logger.isDebug()) {
+ logger.debug(this, "DC Volts: %.1fV, DC current: %.1fA, AC current: %.1fA, mechPower: %.1fkW", dcVoltage / 10.0F,
+ dcCurrent / 10.0F, acCurrent / 10.0F, mechanicalPower / 10.0F);
+ }
+}
+
+/*
+ * Process a DMC_ERRS message which was received from the motor controller.
+ *
+ * This message provides various error and warning status flags in a bitfield.
+ * The bitfield is not processed here but it is made available for other components
+ * (e.g. the webserver to display the various status flags)
+ */
+void BrusaDMC5::processErrors(uint8_t data[])
+{
+ bitfield = (uint32_t) (data[1] | (data[0] << 8) | (data[5] << 16) | (data[4] << 24));
+
+ canMessageLost = false;
+ if (bitfield != 0) {
+ if (bitfield & speedSensorSupply)
+ logger.error(this, "power supply of speed sensor failed");
+ if (bitfield & speedSensor)
+ logger.error(this, "encoder or position sensor delivers faulty signal");
+ if (bitfield & canLimitMessageInvalid)
+ logger.error(this, "limit data CAN message is invalid");
+ if (bitfield & canControlMessageInvalid)
+ logger.error(this, "control data CAN message is invalid");
+ if (bitfield & canLimitMessageLost) {
+ logger.error(this, "timeout of limit CAN message");
+ canMessageLost = true;
+ }
+ if (bitfield & overvoltageSkyConverter)
+ logger.error(this, "over voltage of the internal power supply");
+ if (bitfield & voltageMeasurement)
+ logger.error(this, "differences in the redundant voltage measurement");
+ if (bitfield & shortCircuit)
+ logger.error(this, "short circuit in the power stage");
+ if (bitfield & canControlMessageLost) {
+ logger.error(this, "timeout of control message");
+ canMessageLost = true;
+ }
+ if (bitfield & canControl2MessageLost) {
+ logger.error(this, "timeout of control2 message");
+ canMessageLost = true;
+ }
+ if (bitfield & initalisation)
+ logger.error(this, "error during initialisation");
+ if (bitfield & analogInput)
+ logger.error(this, "an analog input signal is outside its boundaries");
+ if (bitfield & driverShutdown)
+ logger.error(this, "power stage of the motor controller was shut-down in an uncontrolled fashion");
+ if (bitfield & powerMismatch)
+ logger.error(this, "plausibility error between electrical and mechanical power");
+ if (bitfield & motorEeprom)
+ logger.error(this, "error in motor/controller EEPROM module");
+ if (bitfield & storage)
+ logger.error(this, "data consistency check failed in motor controller");
+ if (bitfield & enablePinSignalLost)
+ logger.error(this, "enable signal lost, motor controller shut-down (is imminent)");
+ if (bitfield & canCommunicationStartup)
+ logger.error(this, "motor controller received CAN messages which were not appropriate to its state");
+ if (bitfield & internalSupply)
+ logger.error(this, "problem with the internal power supply");
+ if (bitfield & osTrap)
+ logger.error(this, "severe problem in OS of motor controller");
+ }
+
+ status.overtempController = (bitfield & overtemp) ? true : false;
+ status.overtempMotor = (bitfield & overtempMotor) ? true : false;
+ status.overspeed = (bitfield & overspeed) ? true : false;
+ status.hvUndervoltage = (bitfield & undervoltage) ? true : false;
+ status.hvOvervoltage = (bitfield & overvoltage) ? true : false;
+ status.hvOvercurrent = (bitfield & overcurrent) ? true : false;
+ status.acOvercurrent = (bitfield & acOvercurrent) ? true : false;
+
+ bitfield = (uint32_t) (data[7] | (data[6] << 8));
+
+ if (bitfield != 0) {
+ if (bitfield & externalShutdownPathAw2Off)
+ logger.warn(this, "external shut-down path AW1 off");
+ if (bitfield & externalShutdownPathAw1Off)
+ logger.warn(this, "external shut-down path AW2 off");
+ if (bitfield & driverShutdownPathActive)
+ logger.warn(this, "driver shut-down path active");
+ if (bitfield & powerMismatchDetected)
+ logger.warn(this, "power mismatch detected");
+ if (bitfield & speedSensorSignal)
+ logger.warn(this, "speed sensor signal is bad");
+ if (bitfield & temperatureSensor)
+ logger.warn(this, "invalid data from temperature sensor(s)");
+ }
+
+ status.systemCheckActive = (bitfield & systemCheckActive) ? true : false;
+ status.oscillationLimiter = (bitfield & oscillationLimitControllerActive) ? true : false;
+ status.hvUndervoltage = (bitfield & hvUndervoltage) ? true : false;
+ status.maximumModulationLimiter = (bitfield & maximumModulationLimiter) ? true : false;
+}
+
+/*
+ * Process a DMC_TRQS2 message which was received from the motor controller.
+ *
+ * This message provides information about available torque.
+ */
+void BrusaDMC5::processTorqueLimit(uint8_t data[])
+{
+ maxPositiveTorque = (int16_t) (data[1] | (data[0] << 8)) / 10;
+ minNegativeTorque = (int16_t) (data[3] | (data[2] << 8)) / 10;
+ limiterStateNumber = (uint8_t) data[4];
+
+ if (logger.isDebug()) {
+ logger.debug(this, "torque limit: max positive: %.1fNm, min negative: %.1fNm", maxPositiveTorque / 10.0F, minNegativeTorque / 10.0F,
+ limiterStateNumber);
+ }
+}
+
+/*
+ * Process a DMC_TEMP message which was received from the motor controller.
+ *
+ * This message provides information about motor and inverter temperatures.
+ */
+void BrusaDMC5::processTemperature(uint8_t data[])
+{
+ int16_t temperaturePowerStage;
+ temperaturePowerStage = (int16_t) (data[1] | (data[0] << 8)) * 5;
+ temperatureMotor = (int16_t) (data[3] | (data[2] << 8)) * 5;
+ temperatureController = (int16_t) (data[4] - 50) * 10;
+ if (logger.isDebug()) {
+ logger.debug(this, "temperature: powerStage: %.1fC, motor: %.1fC, system: %.1fC", temperaturePowerStage / 10.0F, temperatureMotor / 10.0F,
+ temperatureController / 10.0F);
+ }
+ if (temperaturePowerStage > temperatureController) {
+ temperatureController = temperaturePowerStage;
+ }
+}
+
+/**
+ * Prepare the content of the CAN frames sent to the DMC5 so they don't have to be filled in every tick cycle
+ */
+void BrusaDMC5::prepareCanMessages()
+{
+ BrusaDMC5Configuration *config = (BrusaDMC5Configuration *) getConfiguration();
+
+ canHandlerEv.prepareOutputFrame(&outputFrameControl, DMC5_CAN_ID_CONTROL);
+
+ canHandlerEv.prepareOutputFrame(&outputFrameControl2, DMC5_CAN_ID_CONTROL_2);
+// slew rate is not working in firmware --> use GEVCU's own implementation and leave value at zero
+// outputFrameControl2.data.bytes[0] = ((constrain(config->slewRate, 0, 100) * 655) & 0xFF00) >> 8;
+// outputFrameControl2.data.bytes[1] = ((constrain(config->slewRate, 0, 100) * 655) & 0x00FF);
+// outputFrameControl2.data.bytes[2] = ((constrain(config->slewRate, 0, 100) * 655) & 0xFF00) >> 8;
+// outputFrameControl2.data.bytes[3] = ((constrain(config->slewRate, 0, 100) * 655) & 0x00FF);
+ outputFrameControl2.data.bytes[4] = ((constrain(config->maxMechanicalPowerMotor, 0, 2621) * 25) & 0xFF00) >> 8;
+ outputFrameControl2.data.bytes[5] = ((constrain(config->maxMechanicalPowerMotor, 0, 2621) * 25) & 0x00FF);
+ outputFrameControl2.data.bytes[6] = ((constrain(config->maxMechanicalPowerRegen, 0, 2621) * 25) & 0xFF00) >> 8;
+ outputFrameControl2.data.bytes[7] = ((constrain(config->maxMechanicalPowerRegen, 0, 2621) * 25) & 0x00FF);
+
+
+ canHandlerEv.prepareOutputFrame(&outputFrameLimits, DMC5_CAN_ID_LIMIT);
+ outputFrameLimits.data.bytes[0] = (constrain(config->dcVoltLimitMotor, 0, 65535) & 0xFF00) >> 8;
+ outputFrameLimits.data.bytes[1] = (constrain(config->dcVoltLimitMotor, 0, 65535) & 0x00FF);
+ outputFrameLimits.data.bytes[2] = (constrain(config->dcVoltLimitRegen, 0, 65535) & 0xFF00) >> 8;
+ outputFrameLimits.data.bytes[3] = (constrain(config->dcVoltLimitRegen, 0, 65535) & 0x00FF);
+}
+
+
+int16_t BrusaDMC5::getMechanicalPower()
+{
+ return mechanicalPower;
+}
+
+
+/*
+ * Return the device id of this device
+ */
+DeviceId BrusaDMC5::getId()
+{
+ return BRUSA_DMC5;
+}
+
+/*
+ * Load configuration data from EEPROM.
+ *
+ * If not available or the checksum is invalid, default values are chosen.
+ */
+void BrusaDMC5::loadConfiguration()
+{
+ BrusaDMC5Configuration *config = (BrusaDMC5Configuration *) getConfiguration();
+
+ if (!config) { // as lowest sub-class make sure we have a config object
+ config = new BrusaDMC5Configuration();
+ setConfiguration(config);
+ }
+
+ MotorController::loadConfiguration(); // call parent
+
+#ifdef USE_HARD_CODED
+
+ if (false) {
+#else
+ if (prefsHandler->checksumValid()) { //checksum is good, read in the values stored in EEPROM
+#endif
+ uint8_t temp;
+ prefsHandler->read(EEMC_DC_VOLT_LIMIT_MOTOR, &config->dcVoltLimitMotor);
+ prefsHandler->read(EEMC_DC_VOLT_LIMIT_REGEN, &config->dcVoltLimitRegen);
+ prefsHandler->read(EEMC_DC_CURRENT_LIMIT_MOTOR, &config->dcCurrentLimitMotor);
+ prefsHandler->read(EEMC_DC_CURRENT_LIMIT_REGEN, &config->dcCurrentLimitRegen);
+ prefsHandler->read(EEMC_OSCILLATION_LIMITER, &temp);
+ config->enableOscillationLimiter = (temp != 0);
+ } else { //checksum invalid. Reinitialize values and store to EEPROM
+ config->dcVoltLimitMotor = 1000;
+ config->dcVoltLimitRegen = 4200;
+ config->dcCurrentLimitMotor = 3000;
+ config->dcCurrentLimitRegen = 3000;
+ config->enableOscillationLimiter = false;
+ saveConfiguration();
+ }
+ logger.info(this, "DC limit motor: %.1f Volt, DC limit regen: %.1f Volt", config->dcVoltLimitMotor / 10.0f, config->dcVoltLimitRegen / 10.0f);
+ logger.info(this, "DC limit motor: %.1f Amps, DC limit regen: %.1f Amps", config->dcCurrentLimitMotor / 10.0f,
+ config->dcCurrentLimitRegen / 10.0f);
+
+ prepareCanMessages();
+}
+
+/*
+ * Store the current configuration parameters to EEPROM.
+ */
+void BrusaDMC5::saveConfiguration()
+{
+ BrusaDMC5Configuration *config = (BrusaDMC5Configuration *) getConfiguration();
+
+ MotorController::saveConfiguration(); // call parent
+
+ prefsHandler->write(EEMC_DC_VOLT_LIMIT_MOTOR, config->dcVoltLimitMotor);
+ prefsHandler->write(EEMC_DC_VOLT_LIMIT_REGEN, config->dcVoltLimitRegen);
+ prefsHandler->write(EEMC_DC_CURRENT_LIMIT_MOTOR, config->dcCurrentLimitMotor);
+ prefsHandler->write(EEMC_DC_CURRENT_LIMIT_REGEN, config->dcCurrentLimitRegen);
+ prefsHandler->write(EEMC_OSCILLATION_LIMITER, (uint8_t) (config->enableOscillationLimiter ? 1 : 0));
+ prefsHandler->saveChecksum();
+
+ prepareCanMessages();
+}
diff --git a/BrusaDMC5.h b/BrusaDMC5.h
new file mode 100644
index 0000000..64da450
--- /dev/null
+++ b/BrusaDMC5.h
@@ -0,0 +1,190 @@
+/*
+ * BrusaDMC5.h
+ *
+ *
+Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
+
+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 BRUSADMC5_H_
+#define BRUSADMC5_H_
+
+#include
+#include "config.h"
+#include "Status.h"
+#include "Logger.h"
+#include "MotorController.h"
+#include "SystemIO.h"
+#include "TickHandler.h"
+#include "DeviceManager.h"
+#include "DeviceTypes.h"
+
+// CAN bus id's for frames sent to DMC5
+
+#define DMC5_CAN_ID_CONTROL 0x210 // send commands (DMC_CTRL)
+#define DMC5_CAN_ID_LIMIT 0x211 // send limitations (DMC_LIM)
+#define DMC5_CAN_ID_CONTROL_2 0x212 // send commands (DMC_CTRL2)
+
+// CAN bus id's for frames received from DMC5
+
+#define DMC5_CAN_ID_STATUS 0x258 // receive (limit) status message (DMC_TRQS) 01001011000
+#define DMC5_CAN_ID_ACTUAL_VALUES 0x259 // receive actual values (DMC_ACTV) 01001011001
+#define DMC5_CAN_ID_ERRORS 0x25a // receive error codes (DMC_ERR) 01001011010
+#define DMC5_CAN_ID_TORQUE_LIMIT 0x268 // receive torque limit information (DMC_TRQS2) 01001101000
+#define DMC5_CAN_ID_TEMP 0x458 // receive temperature information (DMC_TEMP) 10001011000
+#define DMC5_CAN_MASK 0x1cc // mask for above id's 00111001100
+#define DMC5_CAN_MASKED_ID 0x048 // masked id for id's from 0x258 to 0x268 00001001000
+
+class BrusaDMC5Configuration : public MotorControllerConfiguration
+{
+public:
+ uint16_t dcVoltLimitMotor; // minimum DC voltage limit for motoring in 0.1V
+ uint16_t dcVoltLimitRegen; // maximum DC voltage limit for regen in 0.1V
+ uint16_t dcCurrentLimitMotor; // current limit for motoring in 0.1A
+ uint16_t dcCurrentLimitRegen; // current limit for regen in 0.1A
+
+ bool enableOscillationLimiter; // this will enable the DMC5 oscillation limiter (if also enabled by parameter)
+};
+
+class BrusaDMC5: public MotorController
+{
+public:
+ // Message id=0x258, DMC_TRQS
+ // The value is composed of 2 bytes: (data[1] << 0) | (data[0] << 8)
+ enum DMC5_Status {
+ motorModelLimitation = 1 << 0, // 0x0001, data[1], Motorola bit 15
+ mechanicalPowerLimitation = 1 << 1, // 0x0002, data[1], Motorola bit 14
+ maxTorqueLimitation = 1 << 2, // 0x0004, data[1], Motorola bit 13
+ acCurrentLimitation = 1 << 3, // 0x0008, data[1], Motorola bit 12
+ temperatureLimitation = 1 << 4, // 0x0010, data[1], Motorola bit 11
+ speedLimitation = 1 << 5, // 0x0020, data[1], Motorola bit 10
+ voltageLimitation = 1 << 6, // 0x0040, data[1], Motorola bit 9
+ currentLimitation = 1 << 7, // 0x0080, data[1], Motorola bit 8
+
+ torqueLimitation = 1 << 8, // 0x0100, data[0], Motorola bit 7
+ errorFlag = 1 << 9, // 0x0200, data[0], Motorola bit 6
+ warningFlag = 1 << 10, // 0x0400, data[0], Motorola bit 5
+ slewRateLimitation = 1 << 12, // 0x1000, data[0], Motorola bit 3
+ motorTemperatureLimitation = 1 << 13, // 0x2000, data[0], Motorola bit 2
+ dmc5Running = 1 << 14, // 0x4000, data[0], Motorola bit 1
+ dmc5Ready = 1 << 15 // 0x8000, data[0], Motorola bit 0
+ };
+
+ // Message id=0x25a, DMC_ERR
+ // The value is composed of 2 bytes: (data[7] << 0) | (data[6] << 8)
+ enum DMC5_Warning {
+ systemCheckActive = 1 << 0, // 0x0001, data[6], Motorola bit 63
+ externalShutdownPathAw2Off = 1 << 1, // 0x0002, data[6], Motorola bit 62
+ externalShutdownPathAw1Off = 1 << 2, // 0x0004, data[6], Motorola bit 61
+ oscillationLimitControllerActive = 1 << 3, // 0x0008, data[6], Motorola bit 60
+
+ driverShutdownPathActive = 1 << 10, // 0x0400, data[7], Motorola bit 53
+ powerMismatchDetected = 1 << 11, // 0x0800, data[7], Motorola bit 52
+ speedSensorSignal = 1 << 12, // 0x1000, data[7], Motorola bit 51
+ hvUndervoltage = 1 << 13, // 0x2000, data[7], Motorola bit 50
+ maximumModulationLimiter = 1 << 14, // 0x4000, data[7], Motorola bit 49
+ temperatureSensor = 1 << 15, // 0x8000, data[7], Motorola bit 48
+ };
+
+ // Message id=0x25a, DMC_ERR
+ // The error value is composed of 4 bytes : (data[1] << 0) | (data[0] << 8) | (data[5] << 16) | (data[4] << 24)
+ enum DMC5_Error {
+ speedSensorSupply = 1 << 0, // 0x00000001, data[1], Motorola bit 15
+ speedSensor = 1 << 1, // 0x00000002, data[1], Motorola bit 14
+ canLimitMessageInvalid = 1 << 2, // 0x00000004, data[1], Motorola bit 13
+ canControlMessageInvalid = 1 << 3, // 0x00000008, data[1], Motorola bit 12
+ canLimitMessageLost = 1 << 4, // 0x00000010, data[1], Motorola bit 11
+ overvoltageSkyConverter = 1 << 5, // 0x00000020, data[1], Motorola bit 10
+ voltageMeasurement = 1 << 6, // 0x00000040, data[1], Motorola bit 9
+ shortCircuit = 1 << 7, // 0x00000080, data[1], Motorola bit 8
+
+ canControlMessageLost = 1 << 8, // 0x00000100, data[0], Motorola bit 7
+ overtemp = 1 << 9, // 0x00000200, data[0], Motorola bit 6
+ overtempMotor = 1 << 10, // 0x00000400, data[0], Motorola bit 5
+ overspeed = 1 << 11, // 0x00000800, data[0], Motorola bit 4
+ undervoltage = 1 << 12, // 0x00001000, data[0], Motorola bit 3
+ overvoltage = 1 << 13, // 0x00002000, data[0], Motorola bit 2
+ overcurrent = 1 << 14, // 0x00004000, data[0], Motorola bit 1
+ initalisation = 1 << 15, // 0x00008000, data[0], Motorola bit 0
+
+ analogInput = 1 << 16, // 0x00010000, data[5], Motorola bit 47
+ driverShutdown = 1 << 22, // 0x00400000, data[5], Motorola bit 41
+ powerMismatch = 1 << 23, // 0x00800000, data[5], Motorola bit 40
+
+ canControl2MessageLost = 1 << 24, // 0x01000000, data[4], Motorola bit 39
+ motorEeprom = 1 << 25, // 0x02000000, data[4], Motorola bit 38
+ storage = 1 << 26, // 0x04000000, data[4], Motorola bit 37
+ enablePinSignalLost = 1 << 27, // 0x08000000, data[4], Motorola bit 36
+ canCommunicationStartup = 1 << 28, // 0x10000000, data[4], Motorola bit 35
+ internalSupply = 1 << 29, // 0x20000000, data[4], Motorola bit 34
+ acOvercurrent = 1 << 30, // 0x40000000, data[4], Motorola bit 33
+ osTrap = 1 << 31 // 0x80000000, data[4], Motorola bit 32
+ };
+
+ // Message id=0x210, DMC_CTRL
+ // The value is composed of 1 byte : data[0]
+ enum DMC5_Control {
+ enablePositiveTorqueSpeed = 1 << 0, // 0x01, data[0], Motorola bit 7
+ enableNegativeTorqueSpeed = 1 << 1, // 0x02, data[0], Motorola bit 6
+ clearErrorLatch = 1 << 3, // 0x08, data[0], Motorola bit 4
+ enableOscillationLimiter = 1 << 5, // 0x20, data[0], Motorola bit 2
+ enableSpeedMode = 1 << 6, // 0x40, data[0], Motorola bit 1
+ enablePowerStage = 1 << 7 // 0x80, data[0], Motorola bit 0
+ };
+
+ BrusaDMC5();
+ void handleTick();
+ void handleCanFrame(CAN_FRAME *frame);
+ void handleStateChange(Status::SystemState, Status::SystemState);
+ void tearDown();
+ DeviceId getId();
+ int16_t getMechanicalPower();
+
+ void loadConfiguration();
+ void saveConfiguration();
+
+private:
+ int16_t mechanicalPower; // mechanical power of the motor 0.1 kW
+ int16_t maxPositiveTorque; // max positive available torque in 0.01Nm -> divide by 100 to get Nm
+ int16_t minNegativeTorque; // minimum negative available torque in 0.01Nm
+ uint8_t limiterStateNumber; // state number of active limiter
+ uint32_t bitfield; // various bit fields
+ bool canMessageLost; // if any of the CAN messages was lost
+
+ int tickCounter; // count how many times handleTick() was called
+ CAN_FRAME outputFrameControl; // the output CAN frame for control messages;
+ CAN_FRAME outputFrameControl2; // the output CAN frame for control2 messages;
+ CAN_FRAME outputFrameLimits; // the output CAN frame for limit messages;
+
+ void sendControl();
+ void sendControl2();
+ void sendLimits();
+ void processStatus(uint8_t data[]);
+ void processActualValues(uint8_t data[]);
+ void processErrors(uint8_t data[]);
+ void processTorqueLimit(uint8_t data[]);
+ void processTemperature(uint8_t data[]);
+ void prepareCanMessages();
+
+};
+
+#endif /* BRUSADMC5_H_ */
diff --git a/BrusaMotorController.cpp b/BrusaMotorController.cpp
deleted file mode 100644
index f2b3b75..0000000
--- a/BrusaMotorController.cpp
+++ /dev/null
@@ -1,378 +0,0 @@
-/*
- * BrusaMotorController.cpp
- *
- *
- Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
-
- 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 "BrusaMotorController.h"
-
-/*
- Warning:
- At high speed disable the DMC_EnableRq can be dangerous because a field weakening current is
- needed to achieve zero torque. Switching off the DMC in such a situation will make heavy regenerat-
- ing torque that can't be controlled.
- */
-
-/*
- * Constructor
- */
-BrusaMotorController::BrusaMotorController() : MotorController() {
- prefsHandler = new PrefHandler(BRUSA_DMC5);
- torqueAvailable = 0;
- maxPositiveTorque = 0;
- minNegativeTorque = 0;
- limiterStateNumber = 0;
-
- tickCounter = 0;
-
- commonName = "Brusa DMC5 Inverter";
-}
-
-/*
- * Setup the device if it is enabled in configuration.
- */
-void BrusaMotorController::setup() {
- TickHandler::getInstance()->detach(this);
-
- Logger::info("add device: Brusa DMC5 (id: %X, %X)", BRUSA_DMC5, this);
-
- loadConfiguration();
- MotorController::setup(); // run the parent class version of this function
-
- // register ourselves as observer of 0x258-0x268 and 0x458 can frames
- CanHandler::getInstanceEV()->attach(this, CAN_MASKED_ID_1, CAN_MASK_1, false);
- CanHandler::getInstanceEV()->attach(this, CAN_MASKED_ID_2, CAN_MASK_2, false);
-
- TickHandler::getInstance()->attach(this, CFG_TICK_INTERVAL_MOTOR_CONTROLLER_BRUSA);
-}
-
-/*
- * Process event from the tick handler.
- *
- * The super-class requests desired levels from the throttle and
- * brake and decides which one to apply.
- */
-void BrusaMotorController::handleTick() {
- MotorController::handleTick(); // call parent
- tickCounter++;
-
- sendControl(); // send CTRL every 20ms
- if (tickCounter > 4) {
- sendControl2(); // send CTRL_2 every 100ms
- sendLimits(); // send LIMIT every 100ms
- tickCounter = 0;
- }
-}
-
-/*
- * Send DMC_CTRL message to the motor controller.
- *
- * This message controls the power-stage in the controller, clears the error latch
- * in case errors were detected and requests the desired torque / speed.
- */
-void BrusaMotorController::sendControl() {
- BrusaMotorControllerConfiguration *config = (BrusaMotorControllerConfiguration *)getConfiguration();
- prepareOutputFrame(CAN_ID_CONTROL);
-
- speedRequested = 0;
- torqueRequested = 0;
-
- outputFrame.data.bytes[0] = enablePositiveTorqueSpeed; // | enableNegativeTorqueSpeed;
- if (faulted) {
- outputFrame.data.bytes[0] |= clearErrorLatch;
- } else {
- if ((running || speedActual > 1000) && !getDigital(1)) { // see warning about field weakening current to prevent uncontrollable regen
- outputFrame.data.bytes[0] |= enablePowerStage;
- }
- if (running) {
- if (config->enableOscillationLimiter)
- outputFrame.data.bytes[0] |= enableOscillationLimiter;
-
- if (powerMode == modeSpeed) {
- outputFrame.data.bytes[0] |= enableSpeedMode;
- speedRequested = throttleRequested * config->speedMax / 1000;
- torqueRequested = config->torqueMax; // positive number used for both speed directions
- } else { // torque mode
- speedRequested = config->speedMax; // positive number used for both torque directions
- torqueRequested = throttleRequested * config->torqueMax / 1000;
- }
-
- // set the speed in rpm
- outputFrame.data.bytes[2] = (speedRequested & 0xFF00) >> 8;
- outputFrame.data.bytes[3] = (speedRequested & 0x00FF);
-
- // set the torque in 0.01Nm (GEVCU uses 0.1Nm -> multiply by 10)
- outputFrame.data.bytes[4] = ((torqueRequested * 10) & 0xFF00) >> 8;
- outputFrame.data.bytes[5] = ((torqueRequested * 10) & 0x00FF);
- }
- }
-
- if (Logger::isDebug())
- Logger::debug(BRUSA_DMC5, "requested Speed: %l rpm, requested Torque: %f Nm", speedRequested, (float)torqueRequested/10.0F);
-
- CanHandler::getInstanceEV()->sendFrame(outputFrame);
-}
-
-/*
- * Send DMC_CTRL2 message to the motor controller.
- *
- * This message controls the mechanical power limits for motor- and regen-mode.
- */
-void BrusaMotorController::sendControl2() {
- BrusaMotorControllerConfiguration *config = (BrusaMotorControllerConfiguration *)getConfiguration();
-
- prepareOutputFrame(CAN_ID_CONTROL_2);
- outputFrame.data.bytes[0] = ((config->torqueSlewRate * 10) & 0xFF00) >> 8;
- outputFrame.data.bytes[1] = ((config->torqueSlewRate * 10) & 0x00FF);
- outputFrame.data.bytes[2] = (config->speedSlewRate & 0xFF00) >> 8;
- outputFrame.data.bytes[3] = (config->speedSlewRate & 0x00FF);
- outputFrame.data.bytes[4] = (config->maxMechanicalPowerMotor & 0xFF00) >> 8;
- outputFrame.data.bytes[5] = (config->maxMechanicalPowerMotor & 0x00FF);
- outputFrame.data.bytes[6] = (config->maxMechanicalPowerRegen & 0xFF00) >> 8;
- outputFrame.data.bytes[7] = (config->maxMechanicalPowerRegen & 0x00FF);
-
- CanHandler::getInstanceEV()->sendFrame(outputFrame);
-}
-
-/*
- * Send DMC_LIM message to the motor controller.
- *
- * This message controls the electrical limits in the controller.
- */
-void BrusaMotorController::sendLimits() {
- BrusaMotorControllerConfiguration *config = (BrusaMotorControllerConfiguration *)getConfiguration();
-
- prepareOutputFrame(CAN_ID_LIMIT);
- outputFrame.data.bytes[0] = (config->dcVoltLimitMotor & 0xFF00) >> 8;
- outputFrame.data.bytes[1] = (config->dcVoltLimitMotor & 0x00FF);
- outputFrame.data.bytes[2] = (config->dcVoltLimitRegen & 0xFF00) >> 8;
- outputFrame.data.bytes[3] = (config->dcVoltLimitRegen & 0x00FF);
- outputFrame.data.bytes[4] = (config->dcCurrentLimitMotor & 0xFF00) >> 8;
- outputFrame.data.bytes[5] = (config->dcCurrentLimitMotor & 0x00FF);
- outputFrame.data.bytes[6] = (config->dcCurrentLimitRegen & 0xFF00) >> 8;
- outputFrame.data.bytes[7] = (config->dcCurrentLimitRegen & 0x00FF);
-
- CanHandler::getInstanceEV()->sendFrame(outputFrame);
-}
-
-/*
- * Prepare the CAN transmit frame.
- * Re-sets all parameters in the re-used frame.
- */
-void BrusaMotorController::prepareOutputFrame(uint32_t id) {
- outputFrame.length = 8;
- outputFrame.id = id;
- outputFrame.extended = 0;
- outputFrame.rtr = 0;
-
- outputFrame.data.bytes[1] = 0;
- outputFrame.data.bytes[2] = 0;
- outputFrame.data.bytes[3] = 0;
- outputFrame.data.bytes[4] = 0;
- outputFrame.data.bytes[5] = 0;
- outputFrame.data.bytes[6] = 0;
- outputFrame.data.bytes[7] = 0;
-}
-
-/*
- * Processes an event from the CanHandler.
- *
- * In case a CAN message was received which pass the masking and id filtering,
- * this method is called. Depending on the ID of the CAN message, the data of
- * the incoming message is processed.
- */
-void BrusaMotorController::handleCanFrame( CAN_FRAME *frame) {
- switch (frame->id) {
- case CAN_ID_STATUS:
- processStatus(frame->data.bytes);
- break;
- case CAN_ID_ACTUAL_VALUES:
- processActualValues(frame->data.bytes);
- break;
- case CAN_ID_ERRORS:
- processErrors(frame->data.bytes);
- break;
- case CAN_ID_TORQUE_LIMIT:
- processTorqueLimit(frame->data.bytes);
- break;
- case CAN_ID_TEMP:
- processTemperature(frame->data.bytes);
- break;
- default:
- Logger::warn(BRUSA_DMC5, "received unknown frame id %X", frame->id);
- }
-}
-
-/*
- * Process a DMC_TRQS message which was received from the motor controller.
- *
- * This message provides the general status of the controller as well as
- * available and current torque and speed.
- */
-void BrusaMotorController::processStatus(uint8_t data[]) {
- statusBitfield1 = (uint32_t)(data[1] | (data[0] << 8));
- torqueAvailable = (int16_t)(data[3] | (data[2] << 8)) / 10;
- torqueActual = (int16_t)(data[5] | (data[4] << 8)) / 10;
- speedActual = (int16_t)(data[7] | (data[6] << 8));
-
- if(Logger::isDebug())
- Logger::debug(BRUSA_DMC5, "status: %X, torque avail: %fNm, actual torque: %fNm, speed actual: %drpm", statusBitfield1, (float)torqueAvailable/100.0F, (float)torqueActual/100.0F, speedActual);
-
- ready = (statusBitfield1 & stateReady) != 0 ? true : false;
- running = (statusBitfield1 & stateRunning) != 0 ? true : false;
- faulted = (statusBitfield1 & errorFlag) != 0 ? true : false;
- warning = (statusBitfield1 & warningFlag) != 0 ? true : false;
-}
-
-/*
- * Process a DMC_ACTV message which was received from the motor controller.
- *
- * This message provides information about current electrical conditions and
- * applied mechanical power.
- */
-void BrusaMotorController::processActualValues(uint8_t data[]) {
- dcVoltage = (uint16_t)(data[1] | (data[0] << 8));
- dcCurrent = (int16_t)(data[3] | (data[2] << 8));
- acCurrent = (uint16_t)(data[5] | (data[4] << 8)) / 2.5;
- mechanicalPower = (int16_t)(data[7] | (data[6] << 8)) / 6.25;
-
- if (Logger::isDebug())
- Logger::debug(BRUSA_DMC5, "actual values: DC Volts: %fV, DC current: %fA, AC current: %fA, mechPower: %fkW", (float)dcVoltage / 10.0F, (float)dcCurrent / 10.0F, (float)acCurrent / 10.0F, (float)mechanicalPower / 10.0F);
-}
-
-/*
- * Process a DMC_ERRS message which was received from the motor controller.
- *
- * This message provides various error and warning status flags in a bitfield.
- * The bitfield is not processed here but it is made available for other components
- * (e.g. the webserver to display the various status flags)
- */
-void BrusaMotorController::processErrors(uint8_t data[]) {
- statusBitfield3 = (uint32_t)(data[1] | (data[0] << 8) | (data[5] << 16) | (data[4] << 24));
- statusBitfield2 = (uint32_t)(data[7] | (data[6] << 8));
-
- if (Logger::isDebug())
- Logger::debug(BRUSA_DMC5, "errors: %X, warning: %X", statusBitfield3, statusBitfield2);
-}
-
-/*
- * Process a DMC_TRQS2 message which was received from the motor controller.
- *
- * This message provides information about available torque.
- */
-void BrusaMotorController::processTorqueLimit(uint8_t data[]) {
- maxPositiveTorque = (int16_t)(data[1] | (data[0] << 8)) / 10;
- minNegativeTorque = (int16_t)(data[3] | (data[2] << 8)) / 10;
- limiterStateNumber = (uint8_t)data[4];
-
- if (Logger::isDebug())
- Logger::debug(BRUSA_DMC5, "torque limit: max positive: %fNm, min negative: %fNm", (float) maxPositiveTorque / 10.0F, (float) minNegativeTorque / 10.0F, limiterStateNumber);
-}
-
-/*
- * Process a DMC_TEMP message which was received from the motor controller.
- *
- * This message provides information about motor and inverter temperatures.
- */
-void BrusaMotorController::processTemperature(uint8_t data[]) {
- temperatureInverter = (int16_t)(data[1] | (data[0] << 8)) * 5;
- temperatureMotor = (int16_t)(data[3] | (data[2] << 8)) * 5;
- temperatureSystem = (int16_t)(data[4] - 50) * 10;
-
- if (Logger::isDebug())
- Logger::debug(BRUSA_DMC5, "temperature: inverter: %fC, motor: %fC, system: %fC", (float)temperatureInverter / 10.0F, (float)temperatureMotor / 10.0F, (float)temperatureSystem / 10.0F);
-}
-
-/*
- * Return the device id of this device
- */
-DeviceId BrusaMotorController::getId() {
- return BRUSA_DMC5;
-}
-
-/*
- * Expose the tick interval of this controller
- */
-uint32_t BrusaMotorController::getTickInterval() {
- return CFG_TICK_INTERVAL_MOTOR_CONTROLLER_BRUSA;
-}
-
-/*
- * Load configuration data from EEPROM.
- *
- * If not available or the checksum is invalid, default values are chosen.
- */
-void BrusaMotorController::loadConfiguration() {
- BrusaMotorControllerConfiguration *config = (BrusaMotorControllerConfiguration *)getConfiguration();
-
- if(!config) { // as lowest sub-class make sure we have a config object
- config = new BrusaMotorControllerConfiguration();
- setConfiguration(config);
- }
-
- MotorController::loadConfiguration(); // call parent
-
-#ifdef USE_HARD_CODED
- if (false) {
-#else
-// if (prefsHandler->checksumValid()) { //checksum is good, read in the values stored in EEPROM
- if (false) { //TODO: use eeprom, not fixed values
-#endif
- Logger::debug(BRUSA_DMC5, (char *)Constants::validChecksum);
-// prefsHandler->read(EEMC_, &config->minimumLevel1);
- } else { //checksum invalid. Reinitialize values and store to EEPROM
- Logger::warn(BRUSA_DMC5, (char *)Constants::invalidChecksum);
- config->maxMechanicalPowerMotor = 50000;
- config->maxMechanicalPowerRegen = 0; //TODO: 50000; don't want regen yet !
-
- config->dcVoltLimitMotor = 1000;
- config->dcVoltLimitRegen = 0;//TODO: 1000; don't want regen yet !;
- config->dcCurrentLimitMotor = 0;
- config->dcCurrentLimitRegen = 0;
- config->enableOscillationLimiter = false;
- saveConfiguration();
- }
- Logger::debug(BRUSA_DMC5, "Max mech power motor: %d kW, max mech power regen: %d ", config->maxMechanicalPowerMotor, config->maxMechanicalPowerRegen);
- Logger::debug(BRUSA_DMC5, "DC limit motor: %d Volt, DC limit regen: %d Volt", config->dcVoltLimitMotor, config->dcVoltLimitRegen);
- Logger::debug(BRUSA_DMC5, "DC limit motor: %d Amps, DC limit regen: %d Amps", config->dcCurrentLimitMotor, config->dcCurrentLimitRegen);
-}
-
-/*
- * Store the current configuration parameters to EEPROM.
- */
-void BrusaMotorController::saveConfiguration() {
- BrusaMotorControllerConfiguration *config = (BrusaMotorControllerConfiguration *)getConfiguration();
-
- MotorController::saveConfiguration(); // call parent
-
- //TODO: store to eeprom
-// prefsHandler->write(EEMC_, config->maxMechanicalPowerMotor);
-// prefsHandler->write(EEMC_, config->maxMechanicalPowerRegen);
-// prefsHandler->write(EEMC_, config->dcVoltLimitMotor);
-// prefsHandler->write(EEMC_, config->dcVoltLimitRegen);
-// prefsHandler->write(EEMC_, config->dcCurrentLimitMotor);
-// prefsHandler->write(EEMC_, config->dcCurrentLimitRegen);
-// prefsHandler->write(EEMC_, config->enableOscillationLimiter);
- prefsHandler->saveChecksum();
-}
diff --git a/BrusaMotorController.h b/BrusaMotorController.h
deleted file mode 100644
index e05b2a9..0000000
--- a/BrusaMotorController.h
+++ /dev/null
@@ -1,187 +0,0 @@
-/*
- * BrusaMotorController.h
- *
- *
-Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
-
-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 BRUSAMOTORCONTROLLER_H_
-#define BRUSAMOTORCONTROLLER_H_
-
-#include
-#include "config.h"
-#include "MotorController.h"
-#include "sys_io.h"
-#include "TickHandler.h"
-#include "CanHandler.h"
-#include "DeviceManager.h"
-#include "ichip_2128.h"
-#include "DeviceTypes.h"
-
-// CAN bus id's for frames sent to DMC5
-
-#define CAN_ID_CONTROL 0x210 // send commands (DMC_CTRL)
-#define CAN_ID_LIMIT 0x211 // send limitations (DMC_LIM)
-#define CAN_ID_CONTROL_2 0x212 // send commands (DMC_CTRL2)
-
-// CAN bus id's for frames received from DMC5
-
-#define CAN_ID_STATUS 0x258 // receive (limit) status message (DMC_TRQS) 01001011000
-#define CAN_ID_ACTUAL_VALUES 0x259 // receive actual values (DMC_ACTV) 01001011001
-#define CAN_ID_ERRORS 0x25a // receive error codes (DMC_ERR) 01001011010
-#define CAN_ID_TORQUE_LIMIT 0x268 // receive torque limit information (DMC_TRQS2) 01001101000
-#define CAN_MASK_1 0x7cc // mask for above id's 11111001100
-#define CAN_MASKED_ID_1 0x248 // masked id for id's from 0x258 to 0x268 01001001000
-
-#define CAN_ID_TEMP 0x458 // receive temperature information (DMC_TEMP) 10001011000
-#define CAN_MASK_2 0x7ff // mask for above id's 11111111111
-#define CAN_MASKED_ID_2 0x458 // masked id for id's from 0x258 to 0x268 10001011000
-
-class BrusaMotorControllerConfiguration : public MotorControllerConfiguration {
-public:
- // DMC_CTRL2
- uint16_t maxMechanicalPowerMotor; // maximal mechanical power of motor in 4W steps
- uint16_t maxMechanicalPowerRegen; // maximal mechanical power of regen in 4W steps
-
- // DMC_LIM
- uint16_t dcVoltLimitMotor; // minimum DC voltage limit for motoring in 0.1V
- uint16_t dcVoltLimitRegen; // maximum DC voltage limit for regen in 0.1V
- uint16_t dcCurrentLimitMotor; // current limit for motoring in 0.1A
- uint16_t dcCurrentLimitRegen; // current limit for regen in 0.1A
-
- bool enableOscillationLimiter; // this will enable the DMC5 oscillation limiter (if also enabled by parameter)
-};
-
-class BrusaMotorController: public MotorController, CanObserver {
-public:
- // Message id=0x258, DMC_TRQS
- // The value is composed of 2 bytes: (data[1] << 0) | (data[0] << 8)
- enum Status {
- motorModelLimitation = 1 << 0, // 0x0001
- mechanicalPowerLimitation = 1 << 1, // 0x0002
- maxTorqueLimitation = 1 << 2, // 0x0004
- acCurrentLimitation = 1 << 3, // 0x0008
- temperatureLimitation = 1 << 4, // 0x0010
- speedLimitation = 1 << 5, // 0x0020
- voltageLimitation = 1 << 6, // 0x0040
- currentLimitation = 1 << 7, // 0x0080
- torqueLimitation = 1 << 8, // 0x0100
- errorFlag = 1 << 9, // 0x0200, see DMC_ERR
- warningFlag = 1 << 10, // 0x0400, see DMC_ERR
- slewRateLimitation = 1 << 12, // 0x1000
- motorTemperatureLimitation = 1 << 13, // 0x2000
- stateRunning = 1 << 14, // 0x4000
- stateReady = 1 << 15 // 0x8000
- };
-
- // Message id=0x25a, DMC_ERR
- // The value is composed of 2 bytes: (data[7] << 0) | (data[6] << 8)
- enum Warning {
- systemCheckActive = 1 << 0, // 0x0001
- externalShutdownPathAw2Off = 1 << 1, // 0x0002
- externalShutdownPathAw1Off = 1 << 2, // 0x0004
- oscillationLimitControllerActive = 1 << 3, // 0x0008
- driverShutdownPathActive = 1 << 10, // 0x0400
- powerMismatchDetected = 1 << 11, // 0x0800
- speedSensorSignal = 1 << 12, // 0x1000
- hvUndervoltage = 1 << 13, // 0x2000
- maximumModulationLimiter = 1 << 14, // 0x4000
- temperatureSensor = 1 << 15, // 0x8000
- };
-
- // Message id=0x25a, DMC_ERR
- // The error value is composed of 4 bytes : (data[1] << 0) | (data[0] << 8) | (data[5] << 16) | (data[4] << 24)
- enum Error {
- speedSensorSupply = 1 << 0, // 0x00000001, data[1]
- speedSensor = 1 << 1, // 0x00000002, data[1]
- canLimitMessageInvalid = 1 << 2, // 0x00000004, data[1]
- canControlMessageInvalid = 1 << 3, // 0x00000008, data[1]
- canLimitMessageLost = 1 << 4, // 0x00000010, data[1]
- overvoltageSkyConverter = 1 << 5, // 0x00000020, data[1]
- voltageMeasurement = 1 << 6, // 0x00000040, data[1]
- shortCircuit = 1 << 7, // 0x00000080, data[1]
- canControlMessageLost = 1 << 8, // 0x00000100, data[0]
- overtemp = 1 << 9, // 0x00000200, data[0]
- overtempMotor = 1 << 10, // 0x00000400, data[0]
- overspeed = 1 << 11, // 0x00000800, data[0]
- undervoltage = 1 << 12, // 0x00001000, data[0]
- overvoltage = 1 << 13, // 0x00002000, data[0]
- overcurrent = 1 << 14, // 0x00004000, data[0]
- initalisation = 1 << 15, // 0x00008000, data[0]
- analogInput = 1 << 16, // 0x00010000, data[5]
- driverShutdown = 1 << 22, // 0x00400000, data[5]
- powerMismatch = 1 << 23, // 0x00800000, data[5]
- canControl2MessageLost = 1 << 24, // 0x01000000, data[4]
- motorEeprom = 1 << 25, // 0x02000000, data[4]
- storage = 1 << 26, // 0x04000000, data[4]
- enablePinSignalLost = 1 << 27, // 0x08000000, data[4]
- canCommunicationStartup = 1 << 28, // 0x10000000, data[4]
- internalSupply = 1 << 29, // 0x20000000, data[4]
- acOvercurrent = 1 << 30, // 0x40000000, data[4]
- osTrap = 1 << 31 // 0x80000000, data[4]
- };
-
- // Message id=0x210, DMC_CTRL
- // The value is composed of 1 byte : data[0]
- enum Control {
- enablePositiveTorqueSpeed = 1 << 0, // 0x01
- enableNegativeTorqueSpeed = 1 << 1, // 0x02
- clearErrorLatch = 1 << 3, // 0x08
- enableOscillationLimiter = 1 << 5, // 0x20
- enableSpeedMode = 1 << 6, // 0x40
- enablePowerStage = 1 << 7 // 0x80
- };
-
- BrusaMotorController();
- void handleTick();
- void handleCanFrame(CAN_FRAME *frame);
- void setup();
- DeviceId getId();
- uint32_t getTickInterval();
-
- void loadConfiguration();
- void saveConfiguration();
-
-private:
- // DMC_TRQS2
- int16_t maxPositiveTorque; // max positive available torque in 0.01Nm -> divide by 100 to get Nm
- int16_t minNegativeTorque; // minimum negative available torque in 0.01Nm
- uint8_t limiterStateNumber; // state number of active limiter
-
- int tickCounter; // count how many times handleTick() was called
- PowerMode powerMode; // the desired power mode
- uint8_t controlBitField; // the control bit field to send via DMC_CTRL in data[0]
- CAN_FRAME outputFrame; // the output CAN frame;
-
- void sendControl();
- void sendControl2();
- void sendLimits();
- void prepareOutputFrame(uint32_t);
- void processStatus(uint8_t data[]);
- void processActualValues(uint8_t data[]);
- void processErrors(uint8_t data[]);
- void processTorqueLimit(uint8_t data[]);
- void processTemperature(uint8_t data[]);
-};
-
-#endif /* BRUSAMOTORCONTROLLER_H_ */
diff --git a/BrusaNLG5.cpp b/BrusaNLG5.cpp
new file mode 100644
index 0000000..6c0e07c
--- /dev/null
+++ b/BrusaNLG5.cpp
@@ -0,0 +1,374 @@
+/*
+ * BrusaNLG5.cpp
+ *
+ *
+ Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
+
+ 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 "BrusaNLG5.h"
+
+/*
+ * Constructor
+ */
+BrusaNLG5::BrusaNLG5() : Charger()
+{
+ prefsHandler = new PrefHandler(BRUSA_NLG5);
+ commonName = "Brusa NLG5 Charger";
+
+ errorPresent = false;
+ clearErrorLatch = true;
+ currentLimitControlPilot = 0;
+ currentLimitPowerIndicator = 0;
+ auxBatteryVoltage = 0;
+ extChargeBalance = 0;
+ boosterOutputCurrent = 0;
+ temperatureExtSensor1 = 0;
+ temperatureExtSensor2 = 0;
+ temperatureExtSensor3 = 0;
+ bitfield = 0;
+ canTickCounter = 0;
+}
+
+/**
+ * Tear down the controller in a safe way.
+ */
+void BrusaNLG5::tearDown()
+{
+ Charger::tearDown();
+
+ canHandlerEv.detach(this, NLG5_CAN_MASKED_ID, NLG5_CAN_MASK);
+ sendControl();
+}
+
+/*
+ * Process event from the tick handler.
+ */
+void BrusaNLG5::handleTick()
+{
+ Charger::handleTick(); // call parent
+ sendControl();
+
+ // check if we get a status message, if not received for 1 sec, the charger is not ready
+ if (canTickCounter < 1000) {
+ canTickCounter++;
+ } else {
+ ready = false;
+ running = false;
+ }
+}
+
+/*
+ * Send NLG5_CTL message to the charger.
+ *
+ * The message is used to set the operation mode, enable the charger
+ * and set the current/voltage.
+ */
+void BrusaNLG5::sendControl()
+{
+ BrusaNLG5Configuration *config = (BrusaNLG5Configuration *) getConfiguration();
+ canHandlerEv.prepareOutputFrame(&outputFrame, NLG5_CAN_ID_COMMAND);
+
+ if (powerOn && (ready || running)) {
+ outputFrame.data.bytes[0] |= enable;
+ }
+ if (errorPresent && clearErrorLatch) {
+ outputFrame.data.bytes[0] |= errorLatch;
+ clearErrorLatch = false;
+ }
+ uint16_t maxInputCurrent = constrain(calculateMaximumInputCurrent(), 0, 500);
+ outputFrame.data.bytes[1] = (maxInputCurrent & 0xFF00) >> 8;
+ outputFrame.data.bytes[2] = (maxInputCurrent & 0x00FF);
+
+ uint16_t voltage = calculateOutputVoltage();
+ outputFrame.data.bytes[3] = (constrain(voltage, 0, 10000) & 0xFF00) >> 8;
+ outputFrame.data.bytes[4] = (constrain(voltage, 0, 10000) & 0x00FF);
+
+ uint16_t current = calculateOutputCurrent();
+ outputFrame.data.bytes[5] = (constrain(current, 0, 1500) & 0xFF00) >> 8;
+ outputFrame.data.bytes[6] = (constrain(current, 0, 1500) & 0x00FF);
+ outputFrame.length = 7;
+
+ canHandlerEv.sendFrame(outputFrame);
+}
+
+/**
+ * act on state changes to register ourselves at the tick handler.
+ * This is special for chargers as they should not run while driving in
+ * order not to consume CPU cycles unnecessarily.
+ */
+void BrusaNLG5::handleStateChange(Status::SystemState oldState, Status::SystemState newState)
+{
+ Charger::handleStateChange(oldState, newState);
+
+ if ((newState == Status::charging || newState == Status::batteryHeating) &&
+ oldState != Status::charging && oldState != Status::batteryHeating) {
+ tickHandler.attach(this, CFG_TICK_INTERVAL_CHARGE_NLG5);
+ canHandlerEv.attach(this, NLG5_CAN_MASKED_ID, NLG5_CAN_MASK, false);
+ canTickCounter = 0;
+ } else {
+ if (oldState == Status::charging) {
+ tearDown();
+ }
+ }
+}
+
+/*
+ * Processes an event from the CanHandler.
+ *
+ * In case a CAN message was received which pass the masking and id filtering,
+ * this method is called. Depending on the ID of the CAN message, the data of
+ * the incoming message is processed.
+ */
+void BrusaNLG5::handleCanFrame(CAN_FRAME *frame)
+{
+ switch (frame->id) {
+ case NLG5_CAN_ID_STATUS:
+ processStatus(frame->data.bytes);
+ break;
+ case NLG5_CAN_ID_VALUES_1:
+ processValues1(frame->data.bytes);
+ break;
+ case NLG5_CAN_ID_VALUES_2:
+ processValues2(frame->data.bytes);
+ break;
+ case NLG5_CAN_ID_TEMPERATURE:
+ processTemperature(frame->data.bytes);
+ break;
+ case NLG5_CAN_ID_ERROR:
+ processError(frame->data.bytes);
+ break;
+ }
+}
+
+/*
+ * Process a NLG5_ST message which was received from the charger.
+ *
+ * This message provides the general status of the charger as well as
+ * active limitations.
+ */
+void BrusaNLG5::processStatus(uint8_t data[])
+{
+ bitfield = (uint32_t)((data[1] << 0) | (data[0] << 8) | (data[3] << 16) | (data[2] << 24));
+
+ canTickCounter = 0;
+ ready = true;
+ running = bitfield & hardwareEnabled;
+
+ if ((bitfield & error) && powerOn) {
+ errorPresent = true;
+ if (millis() > 10000) {
+ logger.error(this, "Charger reported an error, terminating charge.");
+ status.setSystemState(Status::error);
+ }
+ }
+
+// bypassDetection1
+// bypassDetection2
+// controlPilotSignal
+// usMainsLevel2
+// usMainsLevel1
+// euMains
+// coolingFan
+// warning
+// automaticChargingActive
+
+// limitPowerMaximum
+// limitPowerControlPilot
+// limitPowerIndicatorInput
+// limitMainsCurrent
+// limitBatteryCurrent
+// limitBatteryVoltage
+// limitBatteryTemperature
+// limitTransformerTemperature
+// limitDiodesTemperature
+// limitPowerStageTemperature
+// limitCapacitorTemperature
+// limitMaximumOutputVoltage
+// limitMaximumOutputCurrent
+// limitMaximumMainsCurrent
+
+ if (logger.isDebug()) {
+ logger.debug(this, "status bitfield: %#08x", bitfield);
+ }
+}
+
+/*
+ * Process a NLG5_ACT_I message which was received from the charger.
+ *
+ * This message provides actual values.
+ */
+void BrusaNLG5::processValues1(uint8_t data[])
+{
+ inputCurrent = (uint16_t)(data[1] | (data[0] << 8));
+ inputVoltage = (uint16_t)(data[3] | (data[2] << 8));
+ batteryVoltage = (uint16_t)(data[5] | (data[4] << 8));
+ batteryCurrent = (uint16_t)(data[7] | (data[6] << 8));
+
+ if (logger.isDebug()) {
+ logger.debug(this, "mains: %.1fV, %.1fA, battery: %.1fV, %.1fA", (float) inputVoltage / 10.0F, (float) inputCurrent / 100.0F, (float) batteryVoltage / 10.0F, (float) batteryCurrent / 100.0F);
+ }
+}
+
+/*
+ * Process a NLG5_ACT_II message which was received from the charger.
+ *
+ * This message provides actual values.
+ */
+void BrusaNLG5::processValues2(uint8_t data[])
+{
+ currentLimitControlPilot = (uint16_t)(data[1] | (data[0] << 8));
+ currentLimitPowerIndicator = (uint8_t)data[2];
+ auxBatteryVoltage = (uint8_t)data[3];
+ extChargeBalance = (uint16_t)(data[5] | (data[4] << 8));
+ boosterOutputCurrent = (uint16_t)(data[7] | (data[6] << 8));
+
+ if (logger.isDebug()) {
+ logger.debug(this, "current limit by control pilot: %.1fA, by power indicator: %.1fA", (float) currentLimitControlPilot / 10.0F, (float) currentLimitPowerIndicator / 10.0F);
+ logger.debug(this, "aux battery: %fV, external charge balance: %.1fAh, booster output; %.1fA", (float) auxBatteryVoltage / 10.0F, (float) extChargeBalance / 100.0F, (float) boosterOutputCurrent / 100.0F);
+ }
+}
+
+/*
+ * Process a NLG5_TEMP message which was received from the charger.
+ *
+ * This message provides various temperature readings.
+ */
+void BrusaNLG5::processTemperature(uint8_t data[])
+{
+ temperature = (uint16_t)(data[1] | (data[0] << 8));
+ temperatureExtSensor1 = (uint16_t)(data[3] | (data[2] << 8));
+ temperatureExtSensor2 = (uint16_t)(data[5] | (data[4] << 8));
+ temperatureExtSensor3 = (uint16_t)(data[7] | (data[6] << 8));
+
+ if (logger.isDebug()) {
+ logger.debug(this, "Temp power stage: %.1fC, Temp ext sensor 1: %.1fC", (float) temperature / 10.0F, (float) temperatureExtSensor1 / 10.0F);
+ logger.debug(this, "Temp ext sensor 2: %.1fC, Temp ext sensor 3: %.1fC", (float) temperatureExtSensor2 / 10.0F, (float) temperatureExtSensor3 / 10.0F);
+ }
+}
+
+/*
+ * Process a NLG5_ERR message which was received from the charger.
+ *
+ * This message provides errors and warnings.
+ */
+void BrusaNLG5::processError(uint8_t data[])
+{
+ bitfield = (uint32_t)((data[1] << 0) | (data[0] << 8) | (data[3] << 16) | (data[2] << 24));
+
+ if (bitfield != 0 && powerOn) {
+ String error;
+
+ appendMessage(error, bitfield, extTemperatureSensor3Defect, "ext temp sensor 3 defect");
+ appendMessage(error, bitfield, extTemperatureSensor2Defect, "ext temp sensor 2 defect");
+ appendMessage(error, bitfield, extTemperatureSensor1Defect, "ext temp sensor 1 defect");
+ appendMessage(error, bitfield, temperatureSensorTransformer, "temp sensor transformer");
+ appendMessage(error, bitfield, temperatureSensorDiodes, "temp sensor diodes");
+ appendMessage(error, bitfield, temperatureSensorPowerStage, "temp sensor power stage");
+ appendMessage(error, bitfield, temperatureSensorCapacitor, "temp sensor capacitor");
+ appendMessage(error, bitfield, batteryPolarity, "battery polarity");
+ appendMessage(error, bitfield, mainFuseDefective, "main fuse defective");
+ appendMessage(error, bitfield, outputFuseDefective, "output fuse defective");
+ appendMessage(error, bitfield, mainsVoltagePlausibility, "mains voltage plausability");
+ appendMessage(error, bitfield, batteryVoltagePlausibility, "battery voltage plausibility");
+ appendMessage(error, bitfield, shortCircuit, "short circuit");
+ appendMessage(error, bitfield, mainsOvervoltage1, "mains overvoltage 1");
+ appendMessage(error, bitfield, mainsOvervoltage2, "mains overvoltage 2");
+ appendMessage(error, bitfield, batteryOvervoltage, "battery overvoltage");
+ appendMessage(error, bitfield, emergencyChargeTime, "emergency charge time");
+ appendMessage(error, bitfield, emergencyAmpHours, "emergency amp hours");
+ appendMessage(error, bitfield, emergencyBatteryVoltage, "emergency battery voltage");
+ appendMessage(error, bitfield, emergencyBatteryTemperature, "emergency battery temperature");
+ appendMessage(error, bitfield, canReceiveOverflow, "CAN receive overflow");
+ appendMessage(error, bitfield, canTransmitOverflow, "CAN transmit overflow");
+ appendMessage(error, bitfield, canOff, "CAN off");
+ appendMessage(error, bitfield, canTimeout, "CAN timeout");
+ appendMessage(error, bitfield, initializationError, "init error");
+ appendMessage(error, bitfield, watchDogTimeout, "watchdog timeout");
+ appendMessage(error, bitfield, crcPowerEeprom, "CRC power eeprom");
+ appendMessage(error, bitfield, crcSystemEeprom, "CRC system eeprom");
+ appendMessage(error, bitfield, crcNVSRAM, "CRC NVSRAM");
+ appendMessage(error, bitfield, crcFlashMemory, "CRC flash memory");
+
+ logger.error(this, "error (%#08x): %s", bitfield, error.c_str());
+ }
+
+ bitfield = (uint32_t)data[4];
+ if (bitfield != 0) {
+ String warning;
+
+ appendMessage(warning, bitfield, saveCharging, "save charging");
+ appendMessage(warning, bitfield, ledDriver, "LED driver");
+ appendMessage(warning, bitfield, controlMessageNotActive, "ctrl msg not active");
+ appendMessage(warning, bitfield, valueOutOfRange, "value out of range");
+ appendMessage(warning, bitfield, limitOvertemperature, "limit over temperature");
+ appendMessage(warning, bitfield, limitLowBatteryVoltage, "limit low battery voltage");
+ appendMessage(warning, bitfield, limitLowMainsVoltage, "limit low mains voltage");
+
+ logger.warn(this, "limit (%#08x): %s", bitfield, warning.c_str());
+ }
+}
+
+/*
+ * Return the device id of this device
+ */
+DeviceId BrusaNLG5::getId()
+{
+ return BRUSA_NLG5;
+}
+
+/*
+ * Load configuration data from EEPROM.
+ *
+ * If not available or the checksum is invalid, default values are chosen.
+ */
+void BrusaNLG5::loadConfiguration()
+{
+ BrusaNLG5Configuration *config = (BrusaNLG5Configuration *) getConfiguration();
+
+ if (!config) { // as lowest sub-class make sure we have a config object
+ config = new BrusaNLG5Configuration();
+ setConfiguration(config);
+ }
+
+ Charger::loadConfiguration(); // call parent
+
+#ifdef USE_HARD_CODED
+
+ if (false) {
+#else
+ if (prefsHandler->checksumValid()) { //checksum is good, read in the values stored in EEPROM
+#endif
+ }
+}
+
+/*
+ * Store the current configuration parameters to EEPROM.
+ */
+void BrusaNLG5::saveConfiguration()
+{
+// BrusaNLG5Configuration *config = (BrusaNLG5Configuration *) getConfiguration();
+
+ Charger::saveConfiguration(); // call parent
+
+ prefsHandler->saveChecksum();
+}
diff --git a/BrusaNLG5.h b/BrusaNLG5.h
new file mode 100644
index 0000000..8af516f
--- /dev/null
+++ b/BrusaNLG5.h
@@ -0,0 +1,191 @@
+/*
+ * BrusaNLG5.h
+ *
+ *
+Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
+
+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 BRUSANLG5_H_
+#define BRUSANLG5_H_
+
+#include
+#include "config.h"
+#include "Status.h"
+#include "SystemIO.h"
+#include "TickHandler.h"
+#include "CanHandler.h"
+#include "DeviceManager.h"
+#include "DeviceTypes.h"
+#include "Charger.h"
+
+// CAN bus id's for frames sent to NLG5
+
+#define NLG5_CAN_ID_COMMAND 0x618 // send commands (NLG5_CTL)
+
+// CAN bus id's for frames received from NLG5
+
+#define NLG5_CAN_ID_STATUS 0x610 // receive status information (NLG5_ST) 11000010000
+#define NLG5_CAN_ID_VALUES_1 0X611 // receive actual values information (NLG5_ACT_I) 11000010001
+#define NLG5_CAN_ID_VALUES_2 0X612 // receive actual values information (NLG5_ACT_II) 11000010010
+#define NLG5_CAN_ID_TEMPERATURE 0X613 // receive debug information (NLG5_TEMP) 11000010011
+#define NLG5_CAN_ID_ERROR 0X614 // receive debug information (NLG5_ERR) 11000010100
+#define NLG5_CAN_MASK 0x7f8 // mask for above id's 11111111000
+#define NLG5_CAN_MASKED_ID 0x610 // masked id for id's from 0x610 to 0x614 11000010000
+
+class BrusaNLG5Configuration : public ChargerConfiguration
+{
+public:
+};
+
+class BrusaNLG5: public Charger, CanObserver
+{
+public:
+ // Message id=0x610, NLG5_ST
+ // The error value is composed of 4 bytes : (data[1] << 0) | (data[0] << 8) | (data[3] << 16) | (data[2] << 24)
+ enum NLG5_Status {
+ limitPowerMaximum = 1 << 0, // 0x00000001, data[1], Motorola bit 15
+ limitPowerControlPilot = 1 << 1, // 0x00000002, data[1], Motorola bit 14
+ limitPowerIndicatorInput = 1 << 2, // 0x00000004, data[1], Motorola bit 13
+ limitMainsCurrent = 1 << 3, // 0x00000008, data[1], Motorola bit 12
+ limitBatteryCurrent = 1 << 4, // 0x00000010, data[1], Motorola bit 11
+ limitBatteryVoltage = 1 << 5, // 0x00000020, data[1], Motorola bit 10
+ bypassDetection1 = 1 << 6, // 0x00000040, data[1], Motorola bit 9
+ bypassDetection2 = 1 << 7, // 0x00000080, data[1], Motorola bit 8
+
+ controlPilotSignal = 1 << 8, // 0x00000100, data[0], Motorola bit 7
+ usMainsLevel2 = 1 << 9, // 0x00000200, data[0], Motorola bit 6
+ usMainsLevel1 = 1 << 10, // 0x00000400, data[0], Motorola bit 5
+ euMains = 1 << 11, // 0x00000800, data[0], Motorola bit 4
+ coolingFan = 1 << 12, // 0x00001000, data[0], Motorola bit 3
+ warning = 1 << 13, // 0x00002000, data[0], Motorola bit 2
+ error = 1 << 14, // 0x00004000, data[0], Motorola bit 1
+ hardwareEnabled = 1 << 15, // 0x00008000, data[0], Motorola bit 0
+
+ automaticChargingActive = 1 << 23, // 0x00800000, data[3], Motorola bit 31
+
+ limitBatteryTemperature = 1 << 24, // 0x01000000, data[2], Motorola bit 23
+ limitTransformerTemperature = 1 << 25, // 0x02000000, data[2], Motorola bit 22
+ limitDiodesTemperature = 1 << 26, // 0x04000000, data[2], Motorola bit 21
+ limitPowerStageTemperature = 1 << 27, // 0x08000000, data[2], Motorola bit 20
+ limitCapacitorTemperature = 1 << 28, // 0x10000000, data[2], Motorola bit 19
+ limitMaximumOutputVoltage = 1 << 29, // 0x20000000, data[2], Motorola bit 18
+ limitMaximumOutputCurrent = 1 << 30, // 0x40000000, data[2], Motorola bit 17
+ limitMaximumMainsCurrent = 1 << 31 // 0x80000000, data[2], Motorola bit 16
+ };
+
+ // Message id=0x614, NLG5_ERR
+ // The error value is composed of 4 bytes : (data[1] << 0) | (data[0] << 8) | (data[3] << 16) | (data[2] << 24)
+ enum NLG5_Error {
+ extTemperatureSensor3Defect = 1 << 0, // 0x00000001, data[1], Motorola bit 15
+ extTemperatureSensor2Defect = 1 << 1, // 0x00000002, data[1], Motorola bit 14
+ extTemperatureSensor1Defect = 1 << 2, // 0x00000004, data[1], Motorola bit 13
+ temperatureSensorTransformer= 1 << 3, // 0x00000008, data[1], Motorola bit 12
+ temperatureSensorDiodes = 1 << 4, // 0x00000010, data[1], Motorola bit 11
+ temperatureSensorPowerStage = 1 << 5, // 0x00000020, data[1], Motorola bit 10
+ temperatureSensorCapacitor = 1 << 6, // 0x00000040, data[1], Motorola bit 9
+ batteryPolarity = 1 << 7, // 0x00000080, data[1], Motorola bit 8
+
+ mainFuseDefective = 1 << 8, // 0x00000100, data[0], Motorola bit 7
+ outputFuseDefective = 1 << 9, // 0x00000200, data[0], Motorola bit 6
+ mainsVoltagePlausibility = 1 << 10, // 0x00000400, data[0], Motorola bit 5
+ batteryVoltagePlausibility = 1 << 11, // 0x00000800, data[0], Motorola bit 4
+ shortCircuit = 1 << 12, // 0x00001000, data[0], Motorola bit 3
+ mainsOvervoltage1 = 1 << 13, // 0x00002000, data[0], Motorola bit 2
+ mainsOvervoltage2 = 1 << 14, // 0x00004000, data[0], Motorola bit 1
+ batteryOvervoltage = 1 << 15, // 0x00008000, data[0], Motorola bit 0
+
+ emergencyChargeTime = 1 << 18, // 0x00040000, data[3], Motorola bit 29
+ emergencyAmpHours = 1 << 19, // 0x00080000, data[3], Motorola bit 28
+ emergencyBatteryVoltage = 1 << 20, // 0x00100000, data[3], Motorola bit 27
+ emergencyBatteryTemperature = 1 << 21, // 0x00200000, data[3], Motorola bit 26
+ canReceiveOverflow = 1 << 22, // 0x00400000, data[3], Motorola bit 25
+ canTransmitOverflow = 1 << 23, // 0x00800000, data[3], Motorola bit 24
+
+ canOff = 1 << 24, // 0x01000000, data[2], Motorola bit 23
+ canTimeout = 1 << 25, // 0x02000000, data[2], Motorola bit 22
+ initializationError = 1 << 26, // 0x04000000, data[2], Motorola bit 21
+ watchDogTimeout = 1 << 27, // 0x08000000, data[2], Motorola bit 20
+ crcPowerEeprom = 1 << 28, // 0x10000000, data[2], Motorola bit 19
+ crcSystemEeprom = 1 << 29, // 0x20000000, data[2], Motorola bit 18
+ crcNVSRAM = 1 << 30, // 0x40000000, data[2], Motorola bit 17
+ crcFlashMemory = 1 << 31 // 0x80000000, data[2], Motorola bit 16
+ };
+
+ // Message id=0x614, NLG_ERR
+ // The value is composed of 1 byte : data[4]
+ enum NLG5_Warning {
+ saveCharging = 1 << 0, // 0x01, data[4], Motorola bit 39
+ ledDriver = 1 << 1, // 0x02, data[4], Motorola bit 38
+ controlMessageNotActive = 1 << 3, // 0x08, data[4], Motorola bit 36
+ valueOutOfRange = 1 << 4, // 0x10, data[4], Motorola bit 35
+ limitOvertemperature = 1 << 5, // 0x20, data[4], Motorola bit 34
+ limitLowBatteryVoltage = 1 << 6, // 0x40, data[4], Motorola bit 33
+ limitLowMainsVoltage = 1 << 7 // 0x80, data[4], Motorola bit 32
+ };
+
+ // Message id=0x618, NLG5COM
+ // The value is composed of 1 byte : data[0]
+ enum NLG5_Command {
+ controlPilotStageC = 1 << 4, // 0x10, data[0], Motorola bit 3
+ facilityVentilation = 1 << 5, // 0x20, data[0], Motorola bit 2
+ errorLatch = 1 << 6, // 0x40, data[0], Motorola bit 1
+ enable = 1 << 7, // 0x80, data[0], Motorola bit 0
+ };
+
+ BrusaNLG5();
+ void handleTick();
+ void handleCanFrame(CAN_FRAME *frame);
+ void handleStateChange(Status::SystemState, Status::SystemState);
+ void tearDown();
+ DeviceId getId();
+
+ void loadConfiguration();
+ void saveConfiguration();
+
+protected:
+
+private:
+ uint32_t bitfield; // various bit fields
+ uint16_t currentLimitControlPilot; // 0 - 100A in 0.1A
+ uint8_t currentLimitPowerIndicator; // 0 - 20A in 0.1A
+ uint8_t auxBatteryVoltage; // 0 - 25V in 0.1V
+ int16_t extChargeBalance; // -327.68 - 327.67Ah in 0.01Ah
+ uint16_t boosterOutputCurrent; // 0 - 50A in 0.01A
+ int16_t temperatureExtSensor1; // -40 - 300 deg C in 0.1 deg C
+ int16_t temperatureExtSensor2; // -40 - 300 deg C in 0.1 deg C
+ int16_t temperatureExtSensor3; // -40 - 300 deg C in 0.1 deg C
+ uint16_t canTickCounter;
+ bool errorPresent;
+ bool clearErrorLatch;
+
+ CAN_FRAME outputFrame; // the output CAN frame;
+
+ void sendControl();
+ void processStatus(uint8_t data[]);
+ void processValues1(uint8_t data[]);
+ void processValues2(uint8_t data[]);
+ void processTemperature(uint8_t data[]);
+ void processError(uint8_t data[]);
+};
+
+#endif /* BRUSANLG5_H_ */
diff --git a/CMakeLists.txt b/CMakeLists.txt
deleted file mode 100644
index 0170bc7..0000000
--- a/CMakeLists.txt
+++ /dev/null
@@ -1,5 +0,0 @@
-project(gevcu)
-
-add_executable(gevcu main.cpp)
-
-install(TARGETS gevcu RUNTIME DESTINATION bin)
diff --git a/CRC8.cpp b/CRC8.cpp
new file mode 100644
index 0000000..68cdd20
--- /dev/null
+++ b/CRC8.cpp
@@ -0,0 +1,39 @@
+#include "CRC8.h"
+
+static const uint8_t crc_table[] = {
+ 0x00, 0x07, 0x0e, 0x09, 0x1c, 0x1b, 0x12, 0x15, 0x38, 0x3f, 0x36, 0x31,
+ 0x24, 0x23, 0x2a, 0x2d, 0x70, 0x77, 0x7e, 0x79, 0x6c, 0x6b, 0x62, 0x65,
+ 0x48, 0x4f, 0x46, 0x41, 0x54, 0x53, 0x5a, 0x5d, 0xe0, 0xe7, 0xee, 0xe9,
+ 0xfc, 0xfb, 0xf2, 0xf5, 0xd8, 0xdf, 0xd6, 0xd1, 0xc4, 0xc3, 0xca, 0xcd,
+ 0x90, 0x97, 0x9e, 0x99, 0x8c, 0x8b, 0x82, 0x85, 0xa8, 0xaf, 0xa6, 0xa1,
+ 0xb4, 0xb3, 0xba, 0xbd, 0xc7, 0xc0, 0xc9, 0xce, 0xdb, 0xdc, 0xd5, 0xd2,
+ 0xff, 0xf8, 0xf1, 0xf6, 0xe3, 0xe4, 0xed, 0xea, 0xb7, 0xb0, 0xb9, 0xbe,
+ 0xab, 0xac, 0xa5, 0xa2, 0x8f, 0x88, 0x81, 0x86, 0x93, 0x94, 0x9d, 0x9a,
+ 0x27, 0x20, 0x29, 0x2e, 0x3b, 0x3c, 0x35, 0x32, 0x1f, 0x18, 0x11, 0x16,
+ 0x03, 0x04, 0x0d, 0x0a, 0x57, 0x50, 0x59, 0x5e, 0x4b, 0x4c, 0x45, 0x42,
+ 0x6f, 0x68, 0x61, 0x66, 0x73, 0x74, 0x7d, 0x7a, 0x89, 0x8e, 0x87, 0x80,
+ 0x95, 0x92, 0x9b, 0x9c, 0xb1, 0xb6, 0xbf, 0xb8, 0xad, 0xaa, 0xa3, 0xa4,
+ 0xf9, 0xfe, 0xf7, 0xf0, 0xe5, 0xe2, 0xeb, 0xec, 0xc1, 0xc6, 0xcf, 0xc8,
+ 0xdd, 0xda, 0xd3, 0xd4, 0x69, 0x6e, 0x67, 0x60, 0x75, 0x72, 0x7b, 0x7c,
+ 0x51, 0x56, 0x5f, 0x58, 0x4d, 0x4a, 0x43, 0x44, 0x19, 0x1e, 0x17, 0x10,
+ 0x05, 0x02, 0x0b, 0x0c, 0x21, 0x26, 0x2f, 0x28, 0x3d, 0x3a, 0x33, 0x34,
+ 0x4e, 0x49, 0x40, 0x47, 0x52, 0x55, 0x5c, 0x5b, 0x76, 0x71, 0x78, 0x7f,
+ 0x6a, 0x6d, 0x64, 0x63, 0x3e, 0x39, 0x30, 0x37, 0x22, 0x25, 0x2c, 0x2b,
+ 0x06, 0x01, 0x08, 0x0f, 0x1a, 0x1d, 0x14, 0x13, 0xae, 0xa9, 0xa0, 0xa7,
+ 0xb2, 0xb5, 0xbc, 0xbb, 0x96, 0x91, 0x98, 0x9f, 0x8a, 0x8d, 0x84, 0x83,
+ 0xde, 0xd9, 0xd0, 0xd7, 0xc2, 0xc5, 0xcc, 0xcb, 0xe6, 0xe1, 0xe8, 0xef,
+ 0xfa, 0xfd, 0xf4, 0xf3
+};
+
+byte CRC8::calculate(uint8_t *data, uint8_t len)
+{
+ uint16_t i;
+ uint16_t crc = 0x0;
+
+ while (len--) {
+ i = (crc ^ *data++) & 0xFF;
+ crc = (crc_table[i] ^ (crc << 8)) & 0xFF;
+ }
+
+ return crc & 0xFF;
+}
diff --git a/CRC8.h b/CRC8.h
new file mode 100644
index 0000000..4418ce7
--- /dev/null
+++ b/CRC8.h
@@ -0,0 +1,40 @@
+/*
+ * CRC8.cpp
+ *
+ * Util to calculate CRC8
+ *
+ Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
+
+ 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 CRC8_H_
+#define CRC8_H_
+
+#include
+
+
+class CRC8
+{
+public:
+ static byte calculate(byte *data, byte len);
+};
+
+#endif /* CRC8_H_ */
diff --git a/CanBrake.cpp b/CanBrake.cpp
index e49fa65..6144f10 100644
--- a/CanBrake.cpp
+++ b/CanBrake.cpp
@@ -26,201 +26,247 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
#include "CanBrake.h"
-CanBrake::CanBrake() : Throttle() {
- prefsHandler = new PrefHandler(CANBRAKEPEDAL);
-
- rawSignal.input1 = 0;
- rawSignal.input2 = 0;
- rawSignal.input3 = 0;
- ticksNoResponse = 255; // invalidate input signal until response is received
- responseId = 0;
- responseMask = 0x7ff;
- responseExtended = false;
-
- commonName = "CANBus brake";
+CanBrake::CanBrake() : Throttle()
+{
+ prefsHandler = new PrefHandler(CANBRAKEPEDAL);
+ rawSignal.input1 = 0;
+ rawSignal.input2 = 0;
+ rawSignal.input3 = 0;
+ ticksNoResponse = 255; // invalidate input signal until response is received
+ responseId = 0;
+ responseMask = 0x7ff;
+ responseExtended = false;
+
+ commonName = "CANBus brake";
}
-void CanBrake::setup() {
- TickHandler::getInstance()->detach(this);
-
- Logger::info("add device: CanBrake (id: %X, %X)", CANBRAKEPEDAL, this);
-
- loadConfiguration();
- Throttle::setup();
-
- requestFrame.length = 0x08;
- requestFrame.rtr = 0x00;
- requestFrame.extended = 0x00;
-
- CanBrakeConfiguration *config = (CanBrakeConfiguration *)getConfiguration();
- switch (config->carType) {
- case Volvo_S80_Gas:
- // Request: dlc=0x8 fid=0x760 id=0x760 ide=0x0 rtr=0x0 data=0x03,0x22,0x2B,0x0D,0x00,0x00,0x00,0x00 (vida: [0x00, 0x00, 0x07, 0x60, 0x22, 0x2B, 0x0D])
- // Response: dlc=0x8 fid=0x768 id=0x768 ide=0x0 rtr=0x0 data=0x05,0x62,0x2B,0x0D,0x00,0x01,0x00,0x00 (vida: [0x00, 0x00, 0x07, 0x68, 0x62, 0x2B, 0x0D, 0x00, 0x01]), 6th byte
- requestFrame.id = 0x760;
- memcpy(requestFrame.data.bytes, (const uint8_t[]){ 0x03, 0x22, 0x2B, 0x0D, 0x00, 0x00, 0x00, 0x00 }, 8);
- responseId = 0x768;
- break;
- case Volvo_V50_Diesel:
- // Request: dlc=0x08 fid=0xFFFFE id=0x3FFFE ide=0x01 rtr=0x00 data=0xCD,0x11,0xA6,0x00,0x24,0x01,0x00,0x00 ([0x00, 0xf, 0xff, 0xfe, 0xcd, 0x11, 0xa6, 0x00, 0x24, 0x01, 0x00, 0x00])
- // Response: dlc=0x08 fid=0x400021 id=0x21 ide=0x01 rtr=0x00 data=0xCE,0x11,0xE6,0x00,0x24,0x03,0xFD,0x00 (vida: [0x00, 0x40, 0x00, 0x21, 0xce, 0x11, 0xe6, 0x00, 0x24, 0x03, 0xfd, 0x00])
-// requestFrame.id = 0x3FFFE;
-// requestFrame.ide = 0x01;
-// memcpy(requestFrame.data, (uint8_t[]){ 0xce, 0x11, 0xe6, 0x00, 0x24, 0x03, 0xfd, 0x00 }, 8);
-// responseId = 0x21;
-// responseExtended = true;
- break;
- default:
- Logger::error(CANBRAKEPEDAL, "no valid car type defined.");
- }
-
- CanHandler::getInstanceCar()->attach(this, responseId, responseMask, responseExtended);
- TickHandler::getInstance()->attach(this, CFG_TICK_INTERVAL_CAN_THROTTLE);
+void CanBrake::setup()
+{
+ Throttle::setup();
+
+ requestFrame.length = 0x08;
+ requestFrame.rtr = 0x00;
+ requestFrame.extended = 0x00;
+
+ SystemIOConfiguration *config = (SystemIOConfiguration *) systemIO.getConfiguration();
+
+ switch (config->carType) {
+ case SystemIOConfiguration::Volvo_S80_Gas:
+ // Request: dlc=0x8 fid=0x760 id=0x760 ide=0x0 rtr=0x0 data=0x03,0x22,0x2B,0x0D,0x00,0x00,0x00,0x00 (vida: [0x00, 0x00, 0x07, 0x60, 0x22, 0x2B, 0x0D])
+ // Response: dlc=0x8 fid=0x768 id=0x768 ide=0x0 rtr=0x0 data=0x05,0x62,0x2B,0x0D,0x00,0x01,0x00,0x00 (vida: [0x00, 0x00, 0x07, 0x68, 0x62, 0x2B, 0x0D, 0x00, 0x01]), 6th byte
+ requestFrame.id = 0x760;
+ memcpy(requestFrame.data.bytes, (const uint8_t[]) {
+ 0x03, 0x22, 0x2B, 0x0D, 0x00, 0x00, 0x00, 0x00
+ }, 8);
+ responseId = 0x768;
+ ready = true;
+ break;
+
+ case SystemIOConfiguration::Volvo_V50_Diesel:
+ // Request: dlc=0x08 fid=0xFFFFE id=0x3FFFE ide=0x01 rtr=0x00 data=0xCD,0x11,0xA6,0x00,0x24,0x01,0x00,0x00 ([0x00, 0xf, 0xff, 0xfe, 0xcd, 0x11, 0xa6, 0x00, 0x24, 0x01, 0x00, 0x00])
+ // Response: dlc=0x08 fid=0x400021 id=0x21 ide=0x01 rtr=0x00 data=0xCE,0x11,0xE6,0x00,0x24,0x03,0xFD,0x00 (vida: [0x00, 0x40, 0x00, 0x21, 0xce, 0x11, 0xe6, 0x00, 0x24, 0x03, 0xfd, 0x00])
+// requestFrame.id = 0x3FFFE;
+// requestFrame.ide = 0x01;
+// memcpy(requestFrame.data, (uint8_t[]){ 0xce, 0x11, 0xe6, 0x00, 0x24, 0x03, 0xfd, 0x00 }, 8);
+// responseId = 0x21;
+// responseExtended = true;
+// ready = true;
+ break;
+
+ default:
+ logger.error(this, "no valid car type defined.");
+ }
+}
+
+/**
+ * Tear down the device in a safe way.
+ */
+void CanBrake::tearDown()
+{
+ Throttle::tearDown();
+ canHandlerCar.detach(this, responseId, responseMask);
+}
+
+/**
+ * act on messages the super-class does not react upon, like state change
+ * to ready or running which should enable/disable the controller
+ */
+void CanBrake::handleStateChange(Status::SystemState oldState, Status::SystemState newState)
+{
+ Throttle::handleStateChange(oldState, newState);
+
+ if (newState == Status::ready || newState == Status::running) {
+ if (oldState != Status::ready && oldState != Status::running) {
+ canHandlerCar.attach(this, responseId, responseMask, responseExtended);
+ tickHandler.attach(this, CFG_TICK_INTERVAL_CAN_THROTTLE);
+ }
+ } else {
+ if (oldState == Status::ready || oldState == Status::running) {
+ tearDown();
+ }
+ }
}
/*
* Send a request to the ECU.
*
*/
-void CanBrake::handleTick() {
- Throttle::handleTick(); // Call parent handleTick
+void CanBrake::handleTick()
+{
+ Throttle::handleTick(); // Call parent handleTick
- CanHandler::getInstanceCar()->sendFrame(requestFrame);
+ canHandlerCar.sendFrame(requestFrame);
- if (ticksNoResponse < 255) // make sure it doesn't overflow
- ticksNoResponse++;
+ if (ticksNoResponse < 255) { // make sure it doesn't overflow
+ ticksNoResponse++;
+ }
}
/*
* Handle the response of the ECU and calculate the throttle value
*
*/
-void CanBrake::handleCanFrame(CAN_FRAME *frame) {
- CanBrakeConfiguration *config = (CanBrakeConfiguration *)getConfiguration();
-
- if (frame->id == responseId) {
- switch (config->carType) {
- case Volvo_S80_Gas:
- rawSignal.input1 = frame->data.bytes[5];
- break;
- case Volvo_V50_Diesel:
-// rawSignal.input1 = (frame->data.bytes[5] + 1) * frame->data.bytes[6];
- break;
- }
- ticksNoResponse = 0;
- }
+void CanBrake::handleCanFrame(CAN_FRAME *frame)
+{
+ SystemIOConfiguration *config = (SystemIOConfiguration *) systemIO.getConfiguration();
+
+ if (frame->id == responseId) {
+ switch (config->carType) {
+ case SystemIOConfiguration::Volvo_S80_Gas:
+ rawSignal.input1 = frame->data.bytes[5];
+ break;
+
+ case SystemIOConfiguration::Volvo_V50_Diesel:
+// rawSignal.input1 = (frame->data.bytes[5] + 1) * frame->data.bytes[6];
+ break;
+ }
+
+ running = true;
+ ticksNoResponse = 0;
+ }
}
-RawSignalData* CanBrake::acquireRawSignal() {
- return &rawSignal; // should have already happened in the background
+RawSignalData* CanBrake::acquireRawSignal()
+{
+ return &rawSignal; // should have already happened in the background
}
-bool CanBrake::validateSignal(RawSignalData* rawSignal) {
- CanBrakeConfiguration *config = (CanBrakeConfiguration *) getConfiguration();
-
- if (ticksNoResponse >= CFG_CANTHROTTLE_MAX_NUM_LOST_MSG) {
- if (status == OK)
- Logger::error(CANBRAKEPEDAL, "no response on position request received: %d ", ticksNoResponse);
- status = ERR_MISC;
- return false;
- }
- if (rawSignal->input1 > (config->maximumLevel1 + CFG_THROTTLE_TOLERANCE)) {
- if (status == OK)
- Logger::error(CANBRAKEPEDAL, (char *)Constants::valueOutOfRange, rawSignal->input1);
- status = ERR_HIGH_T1;
- return false;
- }
- if (rawSignal->input1 < (config->minimumLevel1 - CFG_THROTTLE_TOLERANCE)) {
- if (status == OK)
- Logger::error(CANBRAKEPEDAL, (char *)Constants::valueOutOfRange, rawSignal->input1);
- status = ERR_LOW_T1;
- return false;
- }
-
- // all checks passed -> brake is working
- if (status != OK)
- Logger::info(CANBRAKEPEDAL, (char *)Constants::normalOperation);
- status = OK;
- return true;
+bool CanBrake::validateSignal(RawSignalData* rawSignal)
+{
+ CanBrakeConfiguration *config = (CanBrakeConfiguration *) getConfiguration();
+
+ if (ticksNoResponse >= CFG_CANTHROTTLE_MAX_NUM_LOST_MSG) {
+ if (throttleStatus == OK) {
+ logger.error(this, "no response on position request received: %d ", ticksNoResponse);
+ }
+
+ throttleStatus = ERR_MISC;
+ return false;
+ }
+
+ if (rawSignal->input1 > (config->maximumLevel + CFG_THROTTLE_TOLERANCE)) {
+ if (throttleStatus == OK) {
+ logger.error(this, VALUE_OUT_OF_RANGE, rawSignal->input1);
+ }
+
+ throttleStatus = ERR_HIGH_T1;
+ return false;
+ }
+
+ if (rawSignal->input1 < (config->minimumLevel - CFG_THROTTLE_TOLERANCE)) {
+ if (throttleStatus == OK) {
+ logger.error(this, VALUE_OUT_OF_RANGE, rawSignal->input1);
+ }
+
+ throttleStatus = ERR_LOW_T1;
+ return false;
+ }
+
+ // all checks passed -> brake is working
+ if (throttleStatus != OK) {
+ logger.info(this, NORMAL_OPERATION);
+ }
+
+ throttleStatus = OK;
+ return true;
}
-uint16_t CanBrake::calculatePedalPosition(RawSignalData* rawSignal) {
- CanBrakeConfiguration *config = (CanBrakeConfiguration *) getConfiguration();
+uint16_t CanBrake::calculatePedalPosition(RawSignalData* rawSignal)
+{
+ CanBrakeConfiguration *config = (CanBrakeConfiguration *) getConfiguration();
- if (config->maximumLevel1 == 0) //brake processing disabled if max is 0
- return 0;
+ if (config->maximumLevel == 0) { //brake processing disabled if max is 0
+ return 0;
+ }
- return normalizeAndConstrainInput(rawSignal->input1, config->minimumLevel1, config->maximumLevel1);
+ return normalizeAndConstrainInput(rawSignal->input1, config->minimumLevel, config->maximumLevel);
}
/*
* Overrides the standard implementation of throttle mapping as different rules apply to
* brake based regen.
*/
-int16_t CanBrake::mapPedalPosition(int16_t pedalPosition) {
- CanBrakeConfiguration *config = (CanBrakeConfiguration *) getConfiguration();
- int16_t brakeLevel, range;
+int16_t CanBrake::mapPedalPosition(int16_t pedalPosition)
+{
+ CanBrakeConfiguration *config = (CanBrakeConfiguration *) getConfiguration();
+ int16_t brakeLevel, range;
- if (pedalPosition == 0) // if brake not pressed, return 0, not minimumRegen !
- return 0;
+ if (pedalPosition == 0) { // if brake not pressed, return 0, not minimumRegen !
+ return 0;
+ }
- range = config->maximumRegen - config->minimumRegen;
- brakeLevel = -10 * range * pedalPosition / 1000;
- brakeLevel -= 10 * config->minimumRegen;
+ range = config->maximumRegen - config->minimumRegen;
+ brakeLevel = -10 * range * pedalPosition / 1000;
+ brakeLevel -= 10 * config->minimumRegen;
- return brakeLevel;
+ return brakeLevel;
}
-DeviceId CanBrake::getId() {
- return CANBRAKEPEDAL;
+DeviceId CanBrake::getId()
+{
+ return CANBRAKEPEDAL;
}
/*
* Return the device type
*/
-DeviceType CanBrake::getType() {
- return (DEVICE_BRAKE);
+DeviceType CanBrake::getType()
+{
+ return (DEVICE_BRAKE);
}
-void CanBrake::loadConfiguration() {
- CanBrakeConfiguration *config = (CanBrakeConfiguration *) getConfiguration();
+void CanBrake::loadConfiguration()
+{
+ CanBrakeConfiguration *config = (CanBrakeConfiguration *) getConfiguration();
- if (!config) { // as lowest sub-class make sure we have a config object
- config = new CanBrakeConfiguration();
- setConfiguration(config);
- }
+ if (!config) { // as lowest sub-class make sure we have a config object
+ config = new CanBrakeConfiguration();
+ setConfiguration(config);
+ }
- Throttle::loadConfiguration(); // call parent
+ Throttle::loadConfiguration(); // call parent
#ifdef USE_HARD_CODED
- if (false) {
+
+ if (false) {
#else
- if (prefsHandler->checksumValid()) { //checksum is good, read in the values stored in EEPROM
+
+ if (prefsHandler->checksumValid()) { //checksum is good, read in the values stored in EEPROM
#endif
- Logger::debug(CANBRAKEPEDAL, (char *)Constants::validChecksum);
- prefsHandler->read(EETH_MIN_ONE, &config->minimumLevel1);
- prefsHandler->read(EETH_MAX_ONE, &config->maximumLevel1);
- prefsHandler->read(EETH_CAR_TYPE, &config->carType);
- } else { //checksum invalid. Reinitialize values and store to EEPROM
- Logger::warn(CANBRAKEPEDAL, (char *)Constants::invalidChecksum);
- config->minimumLevel1 = 2;
- config->maximumLevel1 = 255;
- config->carType = Volvo_S80_Gas;
- saveConfiguration();
- }
- Logger::debug(CANBRAKEPEDAL, "T1 MIN: %l MAX: %l Type: %d", config->minimumLevel1, config->maximumLevel1, config->carType);
+ saveConfiguration();
+ }
+
+ logger.info(this, "T1 MIN: %ld MAX: %ld", config->minimumLevel, config->maximumLevel);
}
/*
* Store the current configuration to EEPROM
*/
-void CanBrake::saveConfiguration() {
- CanBrakeConfiguration *config = (CanBrakeConfiguration *) getConfiguration();
+void CanBrake::saveConfiguration()
+{
+ CanBrakeConfiguration *config = (CanBrakeConfiguration *) getConfiguration();
- Throttle::saveConfiguration(); // call parent
+ Throttle::saveConfiguration(); // call parent
- prefsHandler->write(EETH_MIN_ONE, config->minimumLevel1);
- prefsHandler->write(EETH_MAX_ONE, config->maximumLevel1);
- prefsHandler->write(EETH_CAR_TYPE, config->carType);
- prefsHandler->saveChecksum();
+ prefsHandler->saveChecksum();
}
diff --git a/CanBrake.h b/CanBrake.h
index c4777f5..b5e83ef 100644
--- a/CanBrake.h
+++ b/CanBrake.h
@@ -33,39 +33,40 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
#include "TickHandler.h"
#include "CanHandler.h"
#include "CanThrottle.h"
-#include "constants.h"
-class CanBrakeConfiguration : public ThrottleConfiguration {
+class CanBrakeConfiguration : public ThrottleConfiguration
+{
public:
- uint16_t minimumLevel1, maximumLevel1; // values for when the pedal is at its min and max
- uint16_t carType; // the type of car, so we know how to interpret which bytes
};
-class CanBrake: public Throttle, CanObserver {
+class CanBrake: public Throttle, CanObserver
+{
public:
- CanBrake();
- void setup();
- void handleTick();
- void handleCanFrame(CAN_FRAME *frame);
- DeviceId getId();
- DeviceType getType();
+ CanBrake();
+ void setup();
+ void tearDown();
+ void handleStateChange(Status::SystemState, Status::SystemState);
+ void handleTick();
+ void handleCanFrame(CAN_FRAME *frame);
+ DeviceId getId();
+ DeviceType getType();
- RawSignalData *acquireRawSignal();
- void loadConfiguration();
- void saveConfiguration();
+ RawSignalData *acquireRawSignal();
+ void loadConfiguration();
+ void saveConfiguration();
protected:
- bool validateSignal(RawSignalData *);
- uint16_t calculatePedalPosition(RawSignalData *);
- int16_t mapPedalPosition(int16_t);
+ bool validateSignal(RawSignalData *);
+ uint16_t calculatePedalPosition(RawSignalData *);
+ int16_t mapPedalPosition(int16_t);
private:
- CAN_FRAME requestFrame; // the request frame sent to the car
- RawSignalData rawSignal; // raw signal
- uint8_t ticksNoResponse; // number of ticks no response was received
- uint32_t responseId; // the CAN id with which the response is sent;
- uint32_t responseMask; // the mask for the responseId
- bool responseExtended; // if the response is expected as an extended frame
+ CAN_FRAME requestFrame; // the request frame sent to the car
+ RawSignalData rawSignal; // raw signal
+ uint8_t ticksNoResponse; // number of ticks no response was received
+ uint32_t responseId; // the CAN id with which the response is sent;
+ uint32_t responseMask; // the mask for the responseId
+ bool responseExtended; // if the response is expected as an extended frame
};
#endif /* CAN_BRAKE_H_ */
diff --git a/CanHandler.cpp b/CanHandler.cpp
index 41162f2..3cdd12b 100644
--- a/CanHandler.cpp
+++ b/CanHandler.cpp
@@ -29,96 +29,98 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
#include "CanHandler.h"
-CanHandler *CanHandler::canHandlerEV = NULL;
-CanHandler *CanHandler::canHandlerCar = NULL;
+CanHandler canHandlerEv = CanHandler(CanHandler::CAN_BUS_EV);
+CanHandler canHandlerCar = CanHandler(CanHandler::CAN_BUS_CAR);
/*
- * Private constructor of the can handler
+ * Constructor of the can handler
*/
-CanHandler::CanHandler(CanBusNode canBusNode) {
- this->canBusNode = canBusNode;
-
- // assign the correct bus instance to the pointer
- if (canBusNode == CAN_BUS_CAR)
- bus = &CAN2;
- else
- bus = &CAN;
-
- for (int i=0; i < CFG_CAN_NUM_OBSERVERS; i++)
- observerData[i].observer = NULL;
+CanHandler::CanHandler(CanBusNode canBusNode)
+{
+ this->canBusNode = canBusNode;
+
+ // assign the correct bus instance to the pointer
+ if (canBusNode == CAN_BUS_CAR) {
+ bus = &CAN2;
+ } else {
+ bus = &CAN;
+ }
+
+ for (int i = 0; i < CFG_CAN_NUM_OBSERVERS; i++) {
+ observerData[i].observer = NULL;
+ }
}
/*
- * Retrieve the singleton instance of the CanHandler which is responsible
- * for the EV can bus (CAN0)
- *
- * \retval the CanHandler instance for the EV can bus
+ * Initialization of the CAN bus
*/
-CanHandler* CanHandler::getInstanceEV()
+void CanHandler::setup()
{
- if (canHandlerEV == NULL)
- canHandlerEV = new CanHandler(CAN_BUS_EV);
- return canHandlerEV;
+ // Initialize the canbus at the specified baudrate
+ bus->begin(canBusNode == CAN_BUS_EV ? CFG_CAN0_SPEED : CFG_CAN1_SPEED, 255);
+ bus->setNumTXBoxes(canBusNode == CAN_BUS_EV ? CFG_CAN0_NUM_TX_MAILBOXES : CFG_CAN1_NUM_TX_MAILBOXES);
+ logger.info("CAN%d init ok", (canBusNode == CAN_BUS_EV ? 0 : 1));
}
/*
- * Retrieve the singleton instance of the CanHandler which is responsible
- * for the car can bus (CAN1)
+ * Attach a CanObserver. Can frames which match the id/mask will be forwarded to the observer
+ * via the method handleCanFrame(RX_CAN_FRAME).
+ * Sets up a can bus mailbox if necessary.
*
- * \retval the CanHandler instance for the car can bus
+ * \param observer - the observer object to register (must implement CanObserver class)
+ * \param id - the id of the can frame to listen to
+ * \param mask - the mask to be applied to the frames
+ * \param extended - set if extended frames must be supported
*/
-CanHandler* CanHandler::getInstanceCar()
+void CanHandler::attach(CanObserver* observer, uint32_t id, uint32_t mask, bool extended)
{
- if (canHandlerCar == NULL)
- canHandlerCar = new CanHandler(CAN_BUS_CAR);
- return canHandlerCar;
-}
+ if (isAttached(observer, id, mask)) {
+ logger.warn("CanObserver %#x is already attached with id %#x and mask %#x on bus %d", observer, id, mask, canBusNode);
+ return;
+ }
-/*
- * Initialization of the CAN bus
- */
-void CanHandler::initialize() {
- // Initialize the canbus at the specified baudrate
- bus->init(canBusNode == CAN_BUS_EV ? CFG_CAN0_SPEED : CFG_CAN1_SPEED);
+ int8_t pos = findFreeObserverData();
+
+ if (pos == -1) {
+ logger.error("no free space in CanHandler::observerData, increase its size via CFG_CAN_NUM_OBSERVERS");
+ return;
+ }
+
+ int mailbox = bus->findFreeRXMailbox();
+
+ if (mailbox == -1) {
+ logger.error("no free CAN mailbox on bus %d", canBusNode);
+ return;
+ }
+
+ observerData[pos].id = id;
+ observerData[pos].mask = mask;
+ observerData[pos].extended = extended;
+ observerData[pos].mailbox = mailbox;
+ observerData[pos].observer = observer;
- //Mailboxes are default set up initialized with one MB for TX and the rest for RX
- //That's OK with us so no need to initialize those things there.
+ bus->setRXFilter((uint8_t) mailbox, id, mask, extended);
- Logger::info("CAN%d init ok", (canBusNode == CAN_BUS_EV ? 0 : 1));
+ logger.debug("attached CanObserver (%#x) for id=%#x, mask=%#x, mailbox=%d", observer, id, mask, mailbox);
}
/*
- * Attach a CanObserver. Can frames which match the id/mask will be forwarded to the observer
- * via the method handleCanFrame(RX_CAN_FRAME).
- * Sets up a can bus mailbox if necessary.
+ * Check if a observer is attached to this handler.
*
- * \param observer - the observer object to register (must implement CanObserver class)
- * \param id - the id of the can frame to listen to
- * \param mask - the mask to be applied to the frames
- * \param extended - set if extended frames must be supported
+ * \param observer - observer object to search
+ * \param id - CAN id of the observer to search
+ * \param mask - CAN mask of the observer to search
*/
-void CanHandler::attach(CanObserver* observer, uint32_t id, uint32_t mask, bool extended) {
- int8_t pos = findFreeObserverData();
- if (pos == -1) {
- Logger::error("no free space in CanHandler::observerData, increase its size via CFG_CAN_NUM_OBSERVERS");
- return;
- }
-
- int mailbox = bus->findFreeRXMailbox();
- if (mailbox == -1) {
- Logger::error("no free CAN mailbox on bus %d", canBusNode);
- return;
- }
-
- observerData[pos].id = id;
- observerData[pos].mask = mask;
- observerData[pos].extended = extended;
- observerData[pos].mailbox = mailbox;
- observerData[pos].observer = observer;
-
- bus->setRXFilter((uint8_t)mailbox, id, mask, extended);
-
- Logger::debug("attached CanObserver (%X) for id=%X, mask=%X, mailbox=%d", observer, id, mask, mailbox);
+bool CanHandler::isAttached(CanObserver* observer, uint32_t id, uint32_t mask)
+{
+ for (int i = 0; i < CFG_CAN_NUM_OBSERVERS; i++) {
+ if (observerData[i].observer == observer &&
+ observerData[i].id == id &&
+ observerData[i].mask == mask) {
+ return true;
+ }
+ }
+ return false;
}
/*
@@ -128,16 +130,17 @@ void CanHandler::attach(CanObserver* observer, uint32_t id, uint32_t mask, bool
* \param id - id of the observer to detach (required as one CanObserver may register itself several times)
* \param mask - mask of the observer to detach (dito)
*/
-void CanHandler::detach(CanObserver* observer, uint32_t id, uint32_t mask) {
- for (int i = 0; i < CFG_CAN_NUM_OBSERVERS; i++) {
- if (observerData[i].observer == observer &&
- observerData[i].id == id &&
- observerData[i].mask == mask) {
- observerData[i].observer = NULL;
-
- //TODO: if no more observers on same mailbox, disable its interrupt, reset mailbox
- }
- }
+void CanHandler::detach(CanObserver* observer, uint32_t id, uint32_t mask)
+{
+ for (int i = 0; i < CFG_CAN_NUM_OBSERVERS; i++) {
+ if (observerData[i].observer == observer &&
+ observerData[i].id == id &&
+ observerData[i].mask == mask) {
+ observerData[i].observer = NULL;
+
+ //TODO: if no more observers on same mailbox, disable its interrupt, reset mailbox
+ }
+ }
}
/*
@@ -145,13 +148,14 @@ void CanHandler::detach(CanObserver* observer, uint32_t id, uint32_t mask) {
*
* \param frame - the received can frame to log
*/
-void CanHandler::logFrame(CAN_FRAME& frame) {
- if (Logger::isDebug()) {
- Logger::debug("CAN: dlc=%X fid=%X id=%X ide=%X rtr=%X data=%X,%X,%X,%X,%X,%X,%X,%X",
- frame.length, frame.fid, frame.id, frame.extended, frame.rtr,
- frame.data.bytes[0], frame.data.bytes[1], frame.data.bytes[2], frame.data.bytes[3],
- frame.data.bytes[4], frame.data.bytes[5], frame.data.bytes[6], frame.data.bytes[7]);
- }
+void CanHandler::logFrame(CAN_FRAME& frame)
+{
+ if (logger.isDebug()) {
+ logger.debug("CAN: dlc=%#x fid=%#x id=%#x ide=%#x rtr=%#x data=%#x,%#x,%#x,%#x,%#x,%#x,%#x,%#x",
+ frame.length, frame.fid, frame.id, frame.extended, frame.rtr,
+ frame.data.bytes[0], frame.data.bytes[1], frame.data.bytes[2], frame.data.bytes[3],
+ frame.data.bytes[4], frame.data.bytes[5], frame.data.bytes[6], frame.data.bytes[7]);
+ }
}
/*
@@ -159,63 +163,64 @@ void CanHandler::logFrame(CAN_FRAME& frame) {
*
* \retval array index of the next unused entry in observerData[]
*/
-int8_t CanHandler::findFreeObserverData() {
- for (int i = 0; i < CFG_CAN_NUM_OBSERVERS; i++) {
- if (observerData[i].observer == NULL)
- return i;
- }
- return -1;
+int8_t CanHandler::findFreeObserverData()
+{
+ for (int i = 0; i < CFG_CAN_NUM_OBSERVERS; i++) {
+ if (observerData[i].observer == NULL) {
+ return i;
+ }
+ }
+
+ return -1;
}
/*
- * Find a unused can mailbox according to entries in observerData[].
- *
- * \retval the mailbox index of the next unused mailbox
+ * If a message is available, read it and forward it to registered observers.
*/
-int8_t CanHandler::findFreeMailbox() {
- uint8_t numRxMailboxes = (canBusNode == CAN_BUS_EV ? CFG_CAN0_NUM_RX_MAILBOXES : CFG_CAN1_NUM_RX_MAILBOXES);
- for (uint8_t i = 0; i < numRxMailboxes; i++) {
- bool used = false;
- for (uint8_t j = 0; j < CFG_CAN_NUM_OBSERVERS; j++) {
- if (observerData[j].observer != NULL && observerData[j].mailbox == i)
- used = true;
- }
- if (!used)
- return i;
- }
- return -1;
+void CanHandler::process()
+{
+ static CAN_FRAME frame;
+
+ if (bus->rx_avail()) {
+ bus->get_rx_buff(frame);
+// logFrame(frame);
+
+ for (int i = 0; i < CFG_CAN_NUM_OBSERVERS; i++) {
+ if (observerData[i].observer != NULL) {
+ // Apply mask to frame.id and observer.id. If they match, forward the frame to the observer
+ if ((frame.id & observerData[i].mask) == (observerData[i].id & observerData[i].mask)) {
+ observerData[i].observer->handleCanFrame(&frame);
+ }
+ }
+ }
+ }
}
/*
- * If a message is available, read it and forward it to registered observers.
+ * Prepare the CAN transmit frame.
+ * Re-sets all parameters in the re-used frame.
*/
-void CanHandler::process() {
- static CAN_FRAME frame;
-
- if (bus->rx_avail()) {
- bus->get_rx_buff(frame);
- logFrame(frame);
-
- for (int i = 0; i < CFG_CAN_NUM_OBSERVERS; i++) {
- if (observerData[i].observer != NULL) {
- // Apply mask to frame.id and observer.id. If they match, forward the frame to the observer
- if ((frame.id & observerData[i].mask) == (observerData[i].id & observerData[i].mask))
- observerData[i].observer->handleCanFrame(&frame);
- }
- }
- }
+void CanHandler::prepareOutputFrame(CAN_FRAME *frame, uint32_t id)
+{
+ frame->length = 8;
+ frame->id = id;
+ frame->extended = 0;
+ frame->rtr = 0;
+ frame->data.value = 0;
}
-//Allow the canbus driver to figure out the proper mailbox to use
+//Allow the canbus driver to figure out the proper mailbox to use
//(whatever happens to be open) or queue it to send (if nothing is open)
-void CanHandler::sendFrame(CAN_FRAME& frame) {
- bus->sendFrame(frame);
+void CanHandler::sendFrame(CAN_FRAME& frame)
+{
+ bus->sendFrame(frame);
}
/*
* Default implementation of the CanObserver method. Must be overwritten
* by every sub-class.
*/
-void CanObserver::handleCanFrame(CAN_FRAME *frame) {
- Logger::error("CanObserver does not implement handleCanFrame(), frame.id=%d", frame->id);
+void CanObserver::handleCanFrame(CAN_FRAME *frame)
+{
+ logger.error("CanObserver does not implement handleCanFrame(), frame.id=%d", frame->id);
}
diff --git a/CanHandler.h b/CanHandler.h
index d0931a9..3fcfa55 100644
--- a/CanHandler.h
+++ b/CanHandler.h
@@ -33,50 +33,49 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
#include "variant.h"
#include
#include "Logger.h"
-#include "DeviceManager.h"
-class Device;
-
-class CanObserver {
+class CanObserver // @suppress("Class has a virtual method and non-virtual destructor")
+{
public:
- virtual void handleCanFrame(CAN_FRAME *frame);
+ virtual void handleCanFrame(CAN_FRAME *frame);
};
-class CanHandler {
+class CanHandler
+{
public:
- enum CanBusNode {
- CAN_BUS_EV, // CAN0 is intended to be connected to the EV bus (controller, charger, etc.)
- CAN_BUS_CAR // CAN1 is intended to be connected to the car's high speed bus (the one with the ECU)
- };
+ enum CanBusNode {
+ CAN_BUS_EV, // CAN0 is intended to be connected to the EV bus (controller, charger, etc.)
+ CAN_BUS_CAR // CAN1 is intended to be connected to the car's high speed bus (the one with the ECU)
+ };
- void initialize();
- void attach(CanObserver *observer, uint32_t id, uint32_t mask, bool extended);
- void detach(CanObserver *observer, uint32_t id, uint32_t mask);
- void process();
- void sendFrame(CAN_FRAME& frame);
- static CanHandler *getInstanceCar();
- static CanHandler *getInstanceEV();
+ CanHandler(CanBusNode busNumber);
+ void setup();
+ void attach(CanObserver *observer, uint32_t id, uint32_t mask, bool extended);
+ bool isAttached(CanObserver* observer, uint32_t id, uint32_t mask);
+ void detach(CanObserver *observer, uint32_t id, uint32_t mask);
+ void process();
+ void prepareOutputFrame(CAN_FRAME *frame, uint32_t id);
+ void sendFrame(CAN_FRAME& frame);
+ void logFrame(CAN_FRAME& frame);
protected:
private:
- struct CanObserverData {
- uint32_t id; // what id to listen to
- uint32_t mask; // the CAN frame mask to listen to
- bool extended; // are extended frames expected
- uint8_t mailbox; // which mailbox is this observer assigned to
- CanObserver *observer; // the observer object (e.g. a device)
- };
- static CanHandler *canHandlerEV; // singleton reference to the EV instance (CAN0)
- static CanHandler *canHandlerCar; // singleton reference to the car instance (CAN1)
+ struct CanObserverData {
+ uint32_t id; // what id to listen to
+ uint32_t mask; // the CAN frame mask to listen to
+ bool extended; // are extended frames expected
+ uint8_t mailbox; // which mailbox is this observer assigned to
+ CanObserver *observer; // the observer object (e.g. a device)
+ };
- CanBusNode canBusNode; // indicator to which can bus this instance is assigned to
- CANRaw *bus; // the can bus instance which this CanHandler instance is assigned to
- CanObserverData observerData[CFG_CAN_NUM_OBSERVERS]; // Can observers
+ CanBusNode canBusNode; // indicator to which can bus this instance is assigned to
+ CANRaw *bus; // the can bus instance which this CanHandler instance is assigned to
+ CanObserverData observerData[CFG_CAN_NUM_OBSERVERS]; // Can observers
- CanHandler(CanBusNode busNumber);
- void logFrame(CAN_FRAME& frame);
- int8_t findFreeObserverData();
- int8_t findFreeMailbox();
+ int8_t findFreeObserverData();
};
+extern CanHandler canHandlerEv;
+extern CanHandler canHandlerCar;
+
#endif /* CAN_HANDLER_H_ */
diff --git a/CanIO.cpp b/CanIO.cpp
new file mode 100644
index 0000000..eac4fb5
--- /dev/null
+++ b/CanIO.cpp
@@ -0,0 +1,280 @@
+/*
+ * CanIO.c
+ *
+ Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
+
+ 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 "CanIO.h"
+
+CanIO::CanIO() :
+ Device()
+{
+ prefsHandler = new PrefHandler(CANIO);
+ commonName = "CAN I/O";
+ motorController = NULL;
+ dcdcConverter = NULL;
+}
+
+void CanIO::setup()
+{
+ Device::setup();
+ motorController = deviceManager.getMotorController();
+ dcdcConverter = deviceManager.getDcDcConverter();
+
+ canHandlerEv.attach(this, IO_CAN_MASKED_ID, IO_CAN_MASK, false);
+ canHandlerCar.attach(this, IO_CAN_MASKED_ID_CAR, IO_CAN_MASK_CAR, false);
+
+ ready = true;
+ running = true;
+
+ tickHandler.attach(this, CFG_TICK_INTERVAL_CAN_IO);
+}
+
+/**
+ * Tear down the device in a safe way.
+ */
+void CanIO::tearDown()
+{
+ Device::tearDown();
+ sendIOStatus(); // so the error state is transmitted
+
+ canHandlerEv.detach(this, IO_CAN_MASKED_ID, IO_CAN_MASK);
+}
+
+void CanIO::handleTick()
+{
+ sendIOStatus();
+ sendAnalogData();
+ sendMotorData();
+}
+
+/*
+ * Processes an event from the CanHandler.
+ */
+void CanIO::handleCanFrame(CAN_FRAME *frame)
+{
+ switch (frame->id) {
+ case IO_CAN_ID_GEVCU_EXT_TEMPERATURE:
+ processTemperature(frame->data.byte);
+ break;
+ case IO_CAN_ID_GEVCU_EXT_FLOW_COOL:
+ status.flowCoolant = frame->data.high;
+ break;
+ case IO_CAN_ID_GEVCU_EXT_FLOW_HEAT:
+ status.flowHeater = frame->data.high;
+ break;
+ case IO_CAN_ID_GEVCU_EXT_HEATER:
+ status.heaterPower = frame->data.bytes[0] << 8 | frame->data.bytes[1];
+ status.heaterTemperature = frame->data.bytes[2];
+ break;
+ case IO_CAN_ID_CRUISE_CONTROL: // buttons on the steering wheel
+ motorController->handleCruiseControlButton(getCruiseControlButton(frame->data.byte));
+ break;
+ case IO_CAN_ID_VEHICLE_SPEED:
+ //TODO read vehicle speed
+ break;
+ }
+}
+
+
+/**
+ * Identify pressed cruise control button
+ *
+ * NOTE: This is currently specific to a Volvo S80 Y08, implementation would need to be adjusted to support other car types
+ *
+ * not pressed pressed
+ * Cruise enable: byte5,bit2 (42) byte7,bit2(58)
+ * +: byte5,bit7 (47) byte7,bit7(63)
+ * -: byte4,bit0 (32) byte6,bit0(48)
+ * recall: byte5,bit5 (45) byte7,bit5(61)
+ * 0: byte5,bit4 (44) byte7,bit4(60)
+ *
+ */
+MotorController::CruiseControlButton CanIO::getCruiseControlButton(uint8_t data[]) {
+ if ((data[7] & 1<<2) && !(data[5] & 1<<2))
+ return MotorController::TOGGLE;
+ if ((data[7] & 1<<7) && !(data[5] & 1<<7))
+ return MotorController::PLUS;
+ if ((data[6] & 1<<0) && !(data[4] & 1<<0))
+ return MotorController::MINUS;
+ if ((data[7] & 1<<5) && !(data[5] & 1<<5))
+ return MotorController::RECALL;
+ if ((data[7] & 1<<4) && !(data[5] & 1<<4))
+ return MotorController::DISENGAGE;
+ return MotorController::NONE;
+}
+
+/**
+ * react on additional messages from device manager
+ * in case of quick output changes in SystemIO, it is vital to send additional
+ * IO status messages
+ *
+ */
+void CanIO::handleMessage(uint32_t msgType, void* message)
+{
+ Device::handleMessage(msgType, message);
+
+ switch (msgType) {
+ case MSG_UPDATE:
+ sendIOStatus();
+ break;
+ }
+}
+
+/*
+ * Send the status of the IO over CAN so it can be used by other devices.
+ */
+void CanIO::sendIOStatus()
+{
+ canHandlerEv.prepareOutputFrame(&outputFrame, IO_CAN_ID_GEVCU_STATUS);
+
+ uint16_t rawIO = 0;
+ rawIO |= status.digitalInput[0] ? digitalIn1 : 0;
+ rawIO |= status.digitalInput[1] ? digitalIn2 : 0;
+ rawIO |= status.digitalInput[2] ? digitalIn3 : 0;
+ rawIO |= status.digitalInput[3] ? digitalIn4 : 0;
+ rawIO |= status.digitalOutput[0] ? digitalOut1 : 0;
+ rawIO |= status.digitalOutput[1] ? digitalOut2 : 0;
+ rawIO |= status.digitalOutput[2] ? digitalOut3 : 0;
+ rawIO |= status.digitalOutput[3] ? digitalOut4 : 0;
+ rawIO |= status.digitalOutput[4] ? digitalOut5 : 0;
+ rawIO |= status.digitalOutput[5] ? digitalOut6 : 0;
+ rawIO |= status.digitalOutput[6] ? digitalOut7 : 0;
+ rawIO |= status.digitalOutput[7] ? digitalOut8 : 0;
+
+ outputFrame.data.s0 = rawIO;
+
+ uint16_t logicIO = 0;
+ logicIO |= status.preChargeRelay ? preChargeRelay : 0;
+ logicIO |= status.mainContactor ? mainContactor : 0;
+ logicIO |= status.secondaryContactor ? secondaryContactor : 0;
+// logicIO |= status.fastChargeContactor ? fastChargeContactor : 0;
+ logicIO |= status.enableHeater ? fastChargeContactor : 0; // re-purpose contactor for heater
+
+ logicIO |= status.enableMotor ? enableMotor : 0;
+ logicIO |= status.enableCharger ? enableCharger : 0;
+ logicIO |= status.enableDcDc ? enableDcDc : 0;
+ logicIO |= status.enableHeater ? enableHeater : 0;
+
+ logicIO |= status.heaterValve ? heaterValve : 0;
+ logicIO |= status.heaterPump ? heaterPump : 0;
+ logicIO |= status.coolingPump ? coolingPump : 0;
+ logicIO |= status.coolingFan ? coolingFan : 0;
+
+ logicIO |= status.brakeLight ? brakeLight : 0;
+ logicIO |= status.reverseLight ? reverseLight : 0;
+ logicIO |= status.powerSteering ? powerSteering : 0;
+ logicIO |= status.unused ? unused : 0;
+
+ outputFrame.data.s1 = logicIO;
+
+ outputFrame.data.byte[4] = status.getSystemState();
+
+ canHandlerEv.sendFrame(outputFrame);
+}
+
+/*
+ * Send the values of the analog inputs over CAN so it can be used by other devices.
+ */
+void CanIO::sendAnalogData()
+{
+ canHandlerEv.prepareOutputFrame(&outputFrame, IO_CAN_ID_GEVCU_ANALOG_IO);
+ outputFrame.data.s0 = systemIO.getAnalogIn(0);
+ outputFrame.data.s1 = systemIO.getAnalogIn(1);
+ outputFrame.data.s2 = systemIO.getAnalogIn(2);
+ outputFrame.data.s3 = systemIO.getAnalogIn(3);
+ canHandlerEv.sendFrame(outputFrame);
+}
+
+/*
+ * Send the values of the motor controller over the car's CAN so it can be used by a CAN filter.
+ */
+void CanIO::sendMotorData()
+{
+ canHandlerCar.prepareOutputFrame(&outputFrame, IO_CAN_ID_GEVCU_MOTOR_DATA);
+ if (motorController != NULL) {
+ outputFrame.data.s0 = max(motorController->getSpeedActual(), 0);
+ }
+ if (dcdcConverter != NULL) {
+ outputFrame.data.s1 = (dcdcConverter->isRunning() ? 0x01 : 0x00);
+ }
+ canHandlerCar.sendFrame(outputFrame);
+}
+
+void CanIO::processTemperature(byte bytes[])
+{
+ for (int i = 0; i < CFG_NUMBER_BATTERY_TEMPERATURE_SENSORS; i++) {
+ status.temperatureBattery[i] = (bytes[i] == 0 ? CFG_NO_TEMPERATURE_DATA : (bytes[i] - CFG_CAN_TEMPERATURE_OFFSET) * 10);
+ if (logger.isDebug()) {
+ logger.debug(this, "battery temperature %d: %.1f", i, status.temperatureBattery[i] / 10.0f);
+ }
+ }
+ status.temperatureCoolant = (bytes[6] == 0 ? CFG_NO_TEMPERATURE_DATA : (bytes[6] - CFG_CAN_TEMPERATURE_OFFSET) * 10);
+ status.temperatureExterior = (bytes[7] == 0 ? CFG_NO_TEMPERATURE_DATA : (bytes[7] - CFG_CAN_TEMPERATURE_OFFSET) * 10);
+ if (logger.isDebug()) {
+ logger.debug(this, "coolant temperature: %.1f, exterior temperature %.1f", status.temperatureCoolant / 10.0f,
+ status.temperatureExterior / 10.0f);
+ }
+}
+
+DeviceType CanIO::getType()
+{
+ return DEVICE_IO;
+}
+
+DeviceId CanIO::getId()
+{
+ return CANIO;
+}
+
+void CanIO::loadConfiguration()
+{
+ CanIOConfiguration *config = (CanIOConfiguration *) getConfiguration();
+
+ if (!config) { // as lowest sub-class make sure we have a config object
+ config = new CanIOConfiguration();
+ setConfiguration(config);
+ }
+
+ Device::loadConfiguration(); // call parent
+ logger.info(this, "CAN I/O configuration:");
+
+#ifdef USE_HARD_CODED
+ if (false) {
+#else
+ if (prefsHandler->checksumValid()) { //checksum is good, read in the values stored in EEPROM
+#endif
+// prefsHandler->read(EESYS_, &config->);
+ } else {
+// config-> = 0;
+ saveConfiguration();
+ }
+// logger.info(getId(), "xyz: %d", config->);
+}
+
+void CanIO::saveConfiguration()
+{
+// prefsHandler->write(EESYS_, config->);
+ prefsHandler->saveChecksum();
+}
+
diff --git a/CanIO.h b/CanIO.h
new file mode 100644
index 0000000..b68c7bb
--- /dev/null
+++ b/CanIO.h
@@ -0,0 +1,131 @@
+/*
+ * CanIO.h
+ *
+Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
+
+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 CANIO_H_
+#define CANIO_H_
+
+#include "config.h"
+#include "TickHandler.h"
+#include "DeviceManager.h"
+#include "Status.h"
+#include "MotorController.h"
+#include "DcDcConverter.h"
+
+// messages to send
+#define IO_CAN_ID_GEVCU_STATUS 0x724 // I/O status message id
+#define IO_CAN_ID_GEVCU_ANALOG_IO 0x725 // analog I/O status message id
+#define IO_CAN_ID_GEVCU_MOTOR_DATA 0x129 // motor data for CAN filter
+
+// messages to listen to on EV bus
+#define IO_CAN_ID_GEVCU_EXT_TEMPERATURE 0x728 // Temperature CAN message 11100101000
+#define IO_CAN_ID_GEVCU_EXT_FLOW_HEAT 0x729 // Flow CAN message heater 11100101001
+#define IO_CAN_ID_GEVCU_EXT_FLOW_COOL 0x72a // Flow CAN message cooling 11100101010
+#define IO_CAN_ID_GEVCU_EXT_HEATER 0x72b // Status info from heater 11100101011
+#define IO_CAN_MASK 0x7fc // mask for above id's 11111111100
+#define IO_CAN_MASKED_ID 0x728 // masked id for id's from 0x258 to 0x268 11100101000
+
+// messages to listen to on CAR bus
+#define IO_CAN_ID_CRUISE_CONTROL 0x117 // Info on cruise control buttons 00100010111
+#define IO_CAN_ID_VEHICLE_SPEED 0x000 //
+#define IO_CAN_MASK_CAR 0x7ff // mask for above id's 11111111111
+#define IO_CAN_MASKED_ID_CAR 0x117 // masked id for id's 00100010111
+
+
+class CanIOConfiguration : public DeviceConfiguration
+{
+public:
+};
+
+class CanIO: public Device, public CanObserver
+{
+public:
+ // Message id=0x724, GEVCU_STATUS
+ // The value is composed of 2 bytes: (data[1] << 0) | (data[0] << 8)
+ enum GEVCU_RawIO {
+ digitalOut8 = 1 << 0, // 0x0001, data[1], Motorola bit 15
+ digitalOut7 = 1 << 1, // 0x0002, data[1], Motorola bit 14
+ digitalOut6 = 1 << 2, // 0x0004, data[1], Motorola bit 13
+ digitalOut5 = 1 << 3, // 0x0008, data[1], Motorola bit 12
+ digitalOut4 = 1 << 4, // 0x0010, data[1], Motorola bit 11
+ digitalOut3 = 1 << 5, // 0x0020, data[1], Motorola bit 10
+ digitalOut2 = 1 << 6, // 0x0040, data[1], Motorola bit 9
+ digitalOut1 = 1 << 7, // 0x0080, data[1], Motorola bit 8
+
+ digitalIn4 = 1 << 12, // 0x1000, data[0], Motorola bit 3
+ digitalIn3 = 1 << 13, // 0x2000, data[0], Motorola bit 2
+ digitalIn2 = 1 << 14, // 0x4000, data[0], Motorola bit 1
+ digitalIn1 = 1 << 15 // 0x8000, data[0], Motorola bit 0
+ };
+
+ // The value is composed of 2 bytes: (data[3] << 0) | (data[2] << 8)
+ enum GEVCU_LogicIO {
+ preChargeRelay = 1 << 0, // 0x0001, data[3], Motorola bit 15
+ mainContactor = 1 << 1, // 0x0002, data[3], Motorola bit 14
+ secondaryContactor = 1 << 2, // 0x0004, data[3], Motorola bit 13
+ fastChargeContactor = 1 << 3, // 0x0008, data[3], Motorola bit 12
+
+ enableMotor = 1 << 4, // 0x0010, data[3], Motorola bit 11
+ enableCharger = 1 << 5, // 0x0020, data[3], Motorola bit 10
+ enableDcDc = 1 << 6, // 0x0040, data[3], Motorola bit 9
+ enableHeater = 1 << 7, // 0x0080, data[3], Motorola bit 8
+
+ heaterValve = 1 << 8, // 0x0100, data[2], Motorola bit 7
+ heaterPump = 1 << 9, // 0x0200, data[2], Motorola bit 6
+ coolingPump = 1 << 10, // 0x0400, data[2], Motorola bit 5
+ coolingFan = 1 << 11, // 0x0800, data[2], Motorola bit 4
+
+ brakeLight = 1 << 12, // 0x1000, data[2], Motorola bit 3
+ reverseLight = 1 << 13, // 0x2000, data[2], Motorola bit 2
+ powerSteering = 1 << 14, // 0x4000, data[2], Motorola bit 1
+ unused = 1 << 15 // 0x8000, data[2], Motorola bit 0
+ };
+
+ CanIO();
+ void setup();
+ void tearDown();
+ void handleTick();
+ void handleCanFrame(CAN_FRAME *);
+ void handleMessage(uint32_t, void*);
+ DeviceType getType();
+ DeviceId getId();
+ void loadConfiguration();
+ void saveConfiguration();
+
+protected:
+
+private:
+ CAN_FRAME outputFrame; // the output CAN frame;
+ MotorController *motorController;
+ DcDcConverter *dcdcConverter;
+
+ void processTemperature(byte []);
+ void sendIOStatus();
+ void sendAnalogData();
+ void sendMotorData();
+ MotorController::CruiseControlButton getCruiseControlButton(uint8_t data[]);
+};
+
+#endif /* CANIO_H_ */
diff --git a/CanOBD2.cpp b/CanOBD2.cpp
new file mode 100644
index 0000000..033a650
--- /dev/null
+++ b/CanOBD2.cpp
@@ -0,0 +1,229 @@
+/*
+ * CanOBD2.cpp
+ *
+ * Listens for PID requests over canbus and responds with the relevant information in the proper format
+ *
+ * Currently this is in a very rough state and shouldn't be trusted - Make configuration work soon
+ *
+ Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
+
+ 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 "CanOBD2.h"
+
+CanOBD2::CanOBD2() :
+ Device()
+{
+ prefsHandler = new PrefHandler(CANOBD2);
+ commonName = "CAN OBD2 Interface";
+
+ canHandlerRespond = NULL;
+ canHandlerPoll = NULL;
+
+ arrayPos = 0;
+ lastRequestAnswered = true;
+}
+
+void CanOBD2::setup()
+{
+ Device::setup();
+
+ if (canHandlerRespond != NULL) {
+ canHandlerRespond->attach(this, OBD2_CAN_MASKED_ID_REQUEST, OBD2_CAN_MASK_REQUEST, false);
+ }
+ // if we use the same bus for both, no need to register again as below IDs are covered by those above
+ if (canHandlerPoll != NULL && canHandlerPoll != canHandlerRespond) {
+ canHandlerPoll->attach(this, OBD2_CAN_MASKED_ID_POLL_RESPONSE, OBD2_CAN_MASK_POLL_RESPONSE, false);
+ }
+
+ ready = true;
+ running = true;
+
+ if (canHandlerPoll != NULL) {
+ tickHandler.attach(this, CFG_TICK_INTERVAL_CAN_OBD2);
+ }
+}
+
+void CanOBD2::tearDown()
+{
+ Device::tearDown();
+
+ if (canHandlerRespond != NULL) {
+ canHandlerRespond->detach(this, OBD2_CAN_MASKED_ID_REQUEST, OBD2_CAN_MASK_REQUEST);
+ }
+ if (canHandlerPoll != NULL && canHandlerPoll != canHandlerRespond) {
+ canHandlerPoll->detach(this, OBD2_CAN_MASKED_ID_POLL_RESPONSE, OBD2_CAN_MASK_POLL_RESPONSE);
+ }
+}
+
+uint8_t pids[] = { PID_VEHICLE_SPEED, PID_AMBIENT_TEMP, PID_BAROMETRIC_PRESSURE };
+
+/**
+ * /brief Send a request to the ECU to query the vehicle speed, temperature, etc.
+ */
+void CanOBD2::handleTick()
+{
+ Device::handleTick(); // Call parent handleTick
+ if (lastRequestAnswered && canHandlerPoll != NULL) {
+ CanOBD2Configuration *config = (CanOBD2Configuration *) getConfiguration();
+
+ logger.debug(this, "sending request for PID %X", pids[arrayPos]);
+
+ canHandlerPoll->prepareOutputFrame(&pollFrame, config->canIdOffsetPoll == 255 ? OBD2_CAN_ID_BROADCAST : OBD2_CAN_ID_REQUEST + config->canIdOffsetPoll);
+ pollFrame.data.bytes[0] = 2; // 2 following bytes
+ pollFrame.data.bytes[1] = 1; // show current data
+ pollFrame.data.bytes[2] = pids[arrayPos++];
+ canHandlerPoll->sendFrame(pollFrame);
+ if ((arrayPos + 1) > (sizeof(pids) / sizeof(uint8_t))) {
+ arrayPos = 0;
+ }
+ lastRequestAnswered = false;
+ }
+}
+
+/**
+ * /brief Process the incoming request for data and send the response back.
+ *
+ * @param frame can message with request details
+ */
+void CanOBD2::processRequest(CAN_FRAME *frame)
+{
+ CanOBD2Configuration *config = (CanOBD2Configuration *) getConfiguration();
+ CAN_FRAME outputFrame;
+
+ logger.debug(this, "received OBD2 request for GEVCU data");
+ if (canHandlerRespond != NULL) {
+ canHandlerRespond->prepareOutputFrame(&outputFrame, OBD2_CAN_ID_RESPONSE + config->canIdOffsetRespond);
+ if (OBD2Handler::getInstance()->processRequest(frame->data.bytes, outputFrame.data.bytes)) {
+ canHandlerRespond->sendFrame(outputFrame);
+ }
+ }
+}
+
+/**
+ * /brief Process the incoming response to our own poll request
+ *
+ * @param frame can message to process
+ */
+void CanOBD2::processResponse(CAN_FRAME *frame)
+{
+ if (canHandlerPoll != NULL) {
+ uint8_t* b = frame->data.bytes;
+ uint8_t pid = b[2];
+
+ if(logger.isDebug()) {
+ logger.debug("received pid response: len=%d, mode=%X, pid=%X, data=%d %d %d %d", b[0], b[1], b[2], b[3], b[4], b[5], b[6]);
+ }
+
+ switch(pid) {
+ case PID_VEHICLE_SPEED:
+ status.vehicleSpeed = b[3];
+ logger.debug("v speed: %d kmh, motor speed: %d, ratio (rpm/kmh): %f", status.vehicleSpeed, deviceManager.getMotorController()->getSpeedActual(), deviceManager.getMotorController()->getSpeedActual() / status.vehicleSpeed);
+ break;
+ case PID_AMBIENT_TEMP:
+ status.temperatureExterior = (b[3] - 40) * 10;
+ logger.debug("ext temp: %.1f C", status.temperatureExterior / 10.0f);
+ break;
+ case PID_BAROMETRIC_PRESSURE:
+ status.barometricPressure = b[3];
+ logger.debug("baro: %d kPa", status.barometricPressure);
+ break;
+ }
+ lastRequestAnswered = true;
+ }
+}
+
+void CanOBD2::handleCanFrame(CAN_FRAME *frame)
+{
+ CanOBD2Configuration *config = (CanOBD2Configuration *) getConfiguration();
+
+ // a request from CAN bus for OBD2 data (e.g. from a diagnostic tool)
+ if ((frame->id == OBD2_CAN_ID_REQUEST + config->canIdOffsetRespond) || (frame->id == OBD2_CAN_ID_BROADCAST)) {
+ processRequest(frame);
+ }
+ // a response to our poll for OBD2 data (e.g. containing the vehicle speed)
+ if (frame->id >= OBD2_CAN_ID_RESPONSE && frame->id < OBD2_CAN_ID_RESPONSE + 8) {
+ processResponse(frame);
+ }
+}
+
+DeviceId CanOBD2::getId()
+{
+ return CANOBD2;
+}
+
+void CanOBD2::loadConfiguration()
+{
+ CanOBD2Configuration *config = (CanOBD2Configuration *) getConfiguration();
+
+ if (!config) { // as lowest sub-class make sure we have a config object
+ config = new CanOBD2Configuration();
+ setConfiguration(config);
+ }
+
+ Device::loadConfiguration(); // call parent
+ logger.info(this, "CanOBD2 configuration:");
+
+#ifdef USE_HARD_CODED
+ if (false) {
+#else
+ if (prefsHandler->checksumValid()) { //checksum is good, read in the values stored in EEPROM
+#endif
+ prefsHandler->read(EEOBD2_CAN_BUS_RESPOND, &config->canBusRespond);
+ prefsHandler->read(EEOBD2_CAN_ID_OFFSET_RESPOND, &config->canIdOffsetRespond);
+ prefsHandler->read(EEOBD2_CAN_BUS_POLL, &config->canBusPoll);
+ prefsHandler->read(EEOBD2_CAN_ID_OFFSET_POLL, &config->canIdOffsetPoll);
+ } else { //checksum invalid. Reinitialize values and store to EEPROM
+ config->canBusRespond = 0; // ev can bus
+ config->canIdOffsetRespond = 0;
+ config->canBusPoll = 1; // car's can bus
+ config->canIdOffsetPoll = 255; // broadcast
+ saveConfiguration();
+ }
+
+ if (config->canBusPoll != CFG_OUTPUT_NONE) {
+ canHandlerPoll = (config->canBusPoll == 1 ? &canHandlerCar : &canHandlerEv);
+ }
+ if (config->canBusRespond != CFG_OUTPUT_NONE) {
+ canHandlerRespond = (config->canBusRespond == 1 ? &canHandlerCar : &canHandlerEv);
+ }
+
+ logger.info(this, "bus respond: %d, respond id offset: %d, bus poll: %d, poll id offset: %d", config->canBusRespond, config->canIdOffsetRespond,
+ config->canBusPoll, config->canIdOffsetPoll);
+}
+
+/*
+ * Store the current configuration to EEPROM
+ */
+void CanOBD2::saveConfiguration()
+{
+ CanOBD2Configuration *config = (CanOBD2Configuration *) getConfiguration();
+
+ Device::saveConfiguration(); // call parent
+
+ prefsHandler->write(EEOBD2_CAN_BUS_RESPOND, config->canBusRespond);
+ prefsHandler->write(EEOBD2_CAN_ID_OFFSET_RESPOND, config->canIdOffsetRespond);
+ prefsHandler->write(EEOBD2_CAN_BUS_POLL, config->canBusPoll);
+ prefsHandler->write(EEOBD2_CAN_ID_OFFSET_POLL, config->canIdOffsetPoll);
+ prefsHandler->saveChecksum();
+}
+
diff --git a/CanOBD2.h b/CanOBD2.h
new file mode 100644
index 0000000..7e5d23c
--- /dev/null
+++ b/CanOBD2.h
@@ -0,0 +1,108 @@
+/*
+ * CanOBD2.h
+ *
+Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
+
+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 CAN_OBD2_H_
+#define CAN_OBD2_H_
+
+#include
+#include "config.h"
+#include "TickHandler.h"
+#include "CanHandler.h"
+#include "OBD2Handler.h"
+#include "DeviceManager.h"
+
+#define OBD2_CAN_ID_BROADCAST 0x7df // broadcast address for requests 11111011111
+#define OBD2_CAN_ID_REQUEST 0x7e0 // to 0x7e7, specific request address 11111100000 - 11111100111
+#define OBD2_CAN_MASK_REQUEST 0x7c0 // mask for above id's 11111000000
+#define OBD2_CAN_MASKED_ID_REQUEST 0x7c0 // masked id for id's 0x7df, 0x7e0-0x7e7 11111000000
+
+#define OBD2_CAN_ID_RESPONSE 0x7e8 // to 7ef, response to PID request 11111101000 - 11111101111
+#define OBD2_CAN_MASK_POLL_RESPONSE 0x7f0 // mask for above id's 11111110000
+#define OBD2_CAN_MASKED_ID_POLL_RESPONSE 0x7e0 // masked id for id's 0x7e8-0x7ef 11111100000
+
+// PID LEN DESCRIPTION MIN MAX UNITS FORMULA
+#define PID_SUPPORTED_01_20 0x00 // 4 PIDs supported [01 - 20] Bit encoded [A7..D0] == [PID $01..PID $20
+#define PID_SUPPORTED_21_40 0x20 // 4 PIDs supported [21 - 40] Bit encoded [A7..D0] == [PID $21..PID $40]
+#define PID_SUPPORTED_41_60 0x40 // 4 PIDs supported [41 - 60] Bit encoded [A7..D0] == [PID $41..PID $60]
+#define PID_SUPPORTED_61_80 0x60 // 4 PIDs supported [61 - 80] Bit encoded [A7..D0] == [PID $61..PID $80]
+
+#define PID_VEHICLE_SPEED 0x0D // 1 Vehicle speed 0 255 km/h A
+#define PID_INTAKE_AIR_TEMP 0x0F // 1 Intake air temperature -40 215 °C A − 40
+#define PID_THROTTLE_POS 0x11 // 1 Throttle position 0 100 % 100/255*A
+#define PID_BAROMETRIC_PRESSURE 0x33 // 1 Absolute Barometric Pressure 0 255 kPa A
+#define PID_THROTTLE_POS_RELATIVE 0x45 // 1 Relative throttle position 0 100 % 100/255*A
+#define PID_AMBIENT_TEMP 0x46 // 1 Ambient air temperature -40 215 °C A − 40
+#define PID_THROTTLE_POS_B 0x47 // 1 Absolute throttle position B 0 100 % 100/255*A
+#define PID_THROTTLE_POS_C 0x48 // 1 Absolute throttle position C
+#define PID_THROTTLE_POS_D 0x49 // 1 Accelerator pedal position D
+#define PID_THROTTLE_POS_E 0x4A // 1 Accelerator pedal position E
+#define PID_THROTTLE_POS_F 0x4B // 1 Accelerator pedal position F
+#define PID_THROTTLE_COMMANDED 0x4C // 1 Commanded throttle actuator
+#define PID_TORQUE_DEMAND 0x61 // 1 Demand engine torque % -125 125 % A-125
+#define PID_TORQUE_ACTUAL 0x62 // 1 Actual engine torque % -125 125 % A-125
+#define PID_TORQUE_REFERENCE 0x63 // 2 Engine reference torque 0 65,535 Nm 256*A + B
+#define PID_COOLANT_TEMP 0x67 // 3 Engine coolant temperature
+#define PID_INTAKE_AIR_TEMP2 0x68 // 7 Intake air temperature sensor
+#define PID_THROTTLE_COMMANDED2 0x6C // 5 Commanded throttle actuator control and relative throttle position
+
+class CanOBD2Configuration : public DeviceConfiguration
+{
+public:
+ uint8_t canBusRespond; // whch can bus should we respond to OBD2 requests
+ uint8_t canIdOffsetRespond; // offset for can id on wich we listen to incoming requests (0-7)
+
+ uint8_t canBusPoll; // whch can bus should we poll OBD2 data from
+ uint8_t canIdOffsetPoll; // offset for can id on which we will request OBD2 data from (0-7, 255=broadcast)
+};
+
+class CanOBD2: public Device, CanObserver
+{
+public:
+ CanOBD2();
+ void setup();
+ void tearDown();
+ void handleTick();
+ void handleCanFrame(CAN_FRAME *frame);
+ DeviceId getId();
+
+ void loadConfiguration();
+ void saveConfiguration();
+
+protected:
+
+private:
+ CanHandler *canHandlerRespond;
+ CanHandler *canHandlerPoll;
+ CAN_FRAME pollFrame;
+
+ uint8_t arrayPos;
+ bool lastRequestAnswered;
+
+ void processRequest(CAN_FRAME* frame);
+ void processResponse(CAN_FRAME* frame);
+};
+
+#endif //CAN_OBD2_H_
diff --git a/CanPIDListener.cpp b/CanPIDListener.cpp
deleted file mode 100644
index ec674fb..0000000
--- a/CanPIDListener.cpp
+++ /dev/null
@@ -1,334 +0,0 @@
-/*
- * CanPIDListener.cpp
- *
- * Listens for PID requests over canbus and responds with the relevant information in the proper format
- *
- * Currently this is in a very rough state and shouldn't be trusted - Make configuration work soon
- *
-Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
-
-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 "CanPIDListener.h"
-
-CanPIDListener::CanPIDListener() : Device() {
-
- prefsHandler = new PrefHandler(PIDLISTENER);
-
- responseId = 0;
- responseMask = 0x7ff;
- responseExtended = false;
-}
-
-void CanPIDListener::setup() {
- //TickHandler::getInstance()->detach(this);
-
- loadConfiguration();
- Device::setup();
-
- //TODO: FIXME Quickly coded as hard coded values. This is naughty.
- CanHandler::getInstanceEV()->attach(this, 0x7DF, 0x7DF, false);
- CanHandler::getInstanceEV()->attach(this, 0x7E0, 0x7E0, false);
- //TickHandler::getInstance()->attach(this, CFG_TICK_INTERVAL_CAN_THROTTLE);
-}
-
-/*
- * There is no tick handler because this is the only place we do anything is here
-*
- SAE standard says that this is the format for SAE requests to us:
- byte 0 = # of bytes following
- byte 1 = mode for PID request
- byte 2 = PID requested
-
- However, the sky is the limit for non-SAE frames (modes over 0x09)
- In that case we'll use two bytes for our custom PIDS (sent MSB first like
- all other PID traffic) MSB = byte 2, LSB = byte 3.
-
- These are the PIDs I think we should support (mode 1)
- 0 = lets the other side know which pids we support. A bitfield that runs from MSb of first byte to lsb of last byte (32 bits)
- 1 = Returns 32 bits but we really can only support the first byte which has bit 7 = Malfunction? Bits 0-6 = # of DTCs
- 2 = Freeze DTC
- 4 = Calculated engine load (A * 100 / 255) - Percentage
- 5 = Engine Coolant Temp (A - 40) = Degrees Centigrade
- 0x0C = Engine RPM (A * 256 + B) / 4
- 0x11 = Throttle position (A * 100 / 255) - Percentage
- 0x1C = Standard supported (We return 1 = OBDII)
- 0x1F = runtime since engine start (A*256 + B)
- 0x20 = pids supported (next 32 pids - formatted just like PID 0)
- 0x21 = Distance traveled with fault light lit (A*256 + B) - In km
- 0x2F = Fuel level (A * 100 / 255) - Percentage
- 0x40 = PIDs supported, next 32
- 0x51 = What type of fuel do we use? (We use 8 = electric, presumably.)
- 0x60 = PIDs supported, next 32
- 0x61 = Driver requested torque (A-125) - Percentage
- 0x62 = Actual Torque delivered (A-125) - Percentage
- 0x63 = Reference torque for engine - presumably max torque - A*256 + B - Nm
-
- Mode 3
- Returns DTC (diag trouble codes) - Three per frame
- bits 6-7 = DTC first character (00 = P = Powertrain, 01=C=Chassis, 10=B=Body, 11=U=Network)
- bits 4-5 = Second char (00 = 0, 01 = 1, 10 = 2, 11 = 3)
- bits 0-3 = third char (stored as normal nibble)
- Then next byte has two nibbles for the next 2 characters (fourth char = bits 4-7, fifth = 0-3)
-
- Mode 9 PIDs
- 0x0 = Mode 9 pids supported (same scheme as mode 1)
- 0x9 = How long is ECU name returned by 0x0A?
- 0xA = ASCII string of ECU name. 20 characters are to be returned, I believe 4 at a time
-
- *
- */
-void CanPIDListener::handleCanFrame(CAN_FRAME *frame) {
- CAN_FRAME outputFrame;
- bool ret;
-
- if ((frame->id == 0x7E0) || (frame->id == 0x7DF)) {
- //Do some common setup for our output - we won't pull the trigger unless we need to.
- outputFrame.id = 0x7E8; //first ECU replying - TODO: Perhaps allow this to be configured from 0x7E8 - 0x7EF
- outputFrame.data.bytes[1] = frame->data.bytes[1] + 0x40; //to show that this is a response
- outputFrame.data.bytes[2] = frame->data.bytes[2]; //copy standard PID
- outputFrame.data.bytes[0] = 2;
- if (frame->data.bytes[1] > 0x50) {
- outputFrame.data.bytes[3] = frame->data.bytes[3]; //if using proprietary PIDs then copy second byte too
- outputFrame.data.bytes[0] = 3;
- }
-
- ret = false;
-
- switch (frame->data.bytes[1]) {
- case 1: //show current data
- ret = processShowData(frame, outputFrame);
- break;
- case 2: //show freeze frame data - not sure we'll be supporting this
- break;
- case 3: //show stored diagnostic codes - we can probably map our faults to some existing DTC codes or roll our own
- break;
- case 4: //clear diagnostic trouble codes - If we get this frame we just clear all codes no questions asked.
- break;
- case 6: //test results over CANBus (this replaces mode 5 from non-canbus) - I know nothing of this
- break;
- case 7: //show pending diag codes (current or last driving cycle) - Might just overlap with mode 3
- break;
- case 8: //control operation of on-board systems - this sounds really proprietary and dangerous. Maybe ignore this?
- break;
- case 9: //request vehicle info - We can identify ourselves here but little else
- break;
- case 0x20: //custom PID codes we made up for GEVCU
- break;
- }
-
- //here is where we'd send out response. Right now it sends over canbus but when we support other
- //alteratives they'll be sending here too.
- if (ret) {
- CanHandler::getInstanceEV()->sendFrame(outputFrame);
- }
- }
-}
-
-
-//Process SAE standard PID requests. Function returns whether it handled the request or not.
-bool CanPIDListener::processShowData(CAN_FRAME* inFrame, CAN_FRAME& outFrame) {
- MotorController* motorController = DeviceManager::getInstance()->getMotorController();
- int temp;
-
- switch (inFrame->data.bytes[2]) {
- case 0: //pids 1-0x20 that we support - bitfield
- //returns 4 bytes so immediately indicate that.
- outFrame.data.bytes[0] += 4;
- outFrame.data.bytes[3] = 0b11011000; //pids 1 - 8 - starting with pid 1 in the MSB and going from there
- outFrame.data.bytes[4] = 0b00010000; //pids 9 - 0x10
- outFrame.data.bytes[5] = 0b10000000; //pids 0x11 - 0x18
- outFrame.data.bytes[6] = 0b00010011; //pids 0x19 - 0x20
- return true;
- break;
- case 1: //Returns 32 bits but we really can only support the first byte which has bit 7 = Malfunction? Bits 0-6 = # of DTCs
- outFrame.data.bytes[0] += 4;
- outFrame.data.bytes[3] = 0; //TODO: We aren't properly keeping track of faults yet but when we do fix this.
- outFrame.data.bytes[3] = 0; //these next three are really related to ICE diagnostics
- outFrame.data.bytes[3] = 0; //so ignore them.
- outFrame.data.bytes[3] = 0;
- return true;
- break;
- case 2: //Freeze DTC
- return false; //don't support freeze framing yet. Might be useful in the future.
- break;
- case 4: //Calculated engine load (A * 100 / 255) - Percentage
- temp = (255 * motorController->getTorqueActual()) / motorController->getTorqueAvailable();
- outFrame.data.bytes[0] += 1;
- outFrame.data.bytes[3] = (uint8_t)(temp & 0xFF);
- return true;
- break;
- case 5: //Engine Coolant Temp (A - 40) = Degrees Centigrade
- //our code stores temperatures as a signed integer for tenths of a degree so translate
- temp = motorController->getTemperatureSystem() / 10;
- if (temp < -40) temp = -40;
- if (temp > 215) temp = 215;
- temp += 40;
- outFrame.data.bytes[0] += 1; //returning only one byte
- outFrame.data.bytes[3] = (uint8_t)(temp);
- return true;
- break;
- case 0xC: //Engine RPM (A * 256 + B) / 4
- temp = motorController->getSpeedActual() * 4; //we store in RPM while the PID code wants quarter rpms
- outFrame.data.bytes[0] += 2;
- outFrame.data.bytes[3] = (uint8_t)(temp / 256);
- outFrame.data.bytes[4] = (uint8_t)(temp);
- return true;
- break;
- case 0x11: //Throttle position (A * 100 / 255) - Percentage
- temp = motorController->getThrottle() / 10; //getThrottle returns in 10ths of a percent
- if (temp < 0) temp = 0; //negative throttle can't be shown for OBDII
- temp = (255 * temp) / 100;
- outFrame.data.bytes[0] += 1;
- outFrame.data.bytes[3] = (uint8_t)(temp);
- return true;
- break;
- case 0x1C: //Standard supported (We return 1 = OBDII)
- outFrame.data.bytes[0] += 1;
- outFrame.data.bytes[3] = 1;
- return true;
- break;
- case 0x1F: //runtime since engine start (A*256 + B)
- outFrame.data.bytes[0] += 2;
- outFrame.data.bytes[3] = 0; //TODO: Get the actual runtime.
- outFrame.data.bytes[4] = 0;
- return true;
- break;
- case 0x20: //pids supported (next 32 pids - formatted just like PID 0)
- outFrame.data.bytes[0] += 4;
- outFrame.data.bytes[3] = 0b00000000; //pids 0x21 - 0x28 - starting with pid 0x21 in the MSB and going from there
- outFrame.data.bytes[4] = 0b00000000; //pids 0x29 - 0x30
- outFrame.data.bytes[5] = 0b00000000; //pids 0x31 - 0x38
- outFrame.data.bytes[6] = 0b00000001; //pids 0x39 - 0x40
- return true;
- break;
- case 0x21: //Distance traveled with fault light lit (A*256 + B) - In km
- outFrame.data.bytes[0] += 2;
- outFrame.data.bytes[3] = 0; //TODO: Can we get this information?
- outFrame.data.bytes[4] = 0;
- return true;
- break;
- case 0x2F: //Fuel level (A * 100 / 255) - Percentage
- outFrame.data.bytes[0] += 1;
- outFrame.data.bytes[3] = 0; //TODO: finish BMS interface and get this value
- return true;
- break;
- case 0x40: //PIDs supported, next 32
- outFrame.data.bytes[0] += 4;
- outFrame.data.bytes[3] = 0b00000000; //pids 0x41 - 0x48 - starting with pid 0x41 in the MSB and going from there
- outFrame.data.bytes[4] = 0b00000000; //pids 0x49 - 0x50
- outFrame.data.bytes[5] = 0b10000000; //pids 0x51 - 0x58
- outFrame.data.bytes[6] = 0b00000001; //pids 0x59 - 0x60
- return true;
- break;
- case 0x51: //What type of fuel do we use? (We use 8 = electric, presumably.)
- outFrame.data.bytes[0] += 1;
- outFrame.data.bytes[3] = 8;
- return true;
- break;
- case 0x60: //PIDs supported, next 32
- outFrame.data.bytes[0] += 4;
- outFrame.data.bytes[3] = 0b11100000; //pids 0x61 - 0x68 - starting with pid 0x61 in the MSB and going from there
- outFrame.data.bytes[4] = 0b00000000; //pids 0x69 - 0x70
- outFrame.data.bytes[5] = 0b00000000; //pids 0x71 - 0x78
- outFrame.data.bytes[6] = 0b00000000; //pids 0x79 - 0x80
- return true;
- break;
- case 0x61: //Driver requested torque (A-125) - Percentage
- temp = (100 * motorController->getTorqueRequested()) / motorController->getTorqueAvailable();
- temp += 125;
- outFrame.data.bytes[0] += 1;
- outFrame.data.bytes[3] = (uint8_t)temp;
- return true;
- break;
- case 0x62: //Actual Torque delivered (A-125) - Percentage
- temp = (100 * motorController->getTorqueActual()) / motorController->getTorqueAvailable();
- temp += 125;
- outFrame.data.bytes[0] += 1;
- outFrame.data.bytes[3] = (uint8_t)temp;
- return true;
- break;
- case 0x63: //Reference torque for engine - presumably max torque - A*256 + B - Nm
- temp = motorController->getTorqueAvailable();
- outFrame.data.bytes[0] += 2;
- outFrame.data.bytes[3] = (uint8_t)(temp / 256);
- outFrame.data.bytes[4] = (uint8_t)(temp & 0xFF);
- return true;
- break;
- }
- return false;
-}
-
-bool CanPIDListener::processShowCustomData(CAN_FRAME* inFrame, CAN_FRAME& outFrame) {
- int pid = inFrame->data.bytes[2] * 256 + inFrame->data.bytes[3];
- switch (pid) {
- }
- return false;
-}
-
-DeviceId CanPIDListener::getId() {
- return PIDLISTENER;
-}
-
-void CanPIDListener::loadConfiguration() {
- CanPIDConfiguration *config = (CanPIDConfiguration *) getConfiguration();
-
- if (!config) { // as lowest sub-class make sure we have a config object
- config = new CanPIDConfiguration();
- setConfiguration(config);
- }
-
- Device::loadConfiguration(); // call parent
-
-#ifdef USE_HARD_CODED
- if (false) {
-#else
- if (prefsHandler->checksumValid()) { //checksum is good, read in the values stored in EEPROM
-#endif
- Logger::debug(PIDLISTENER, (char *)Constants::validChecksum);
- //prefsHandler->read(EETH_MIN_ONE, &config->minimumLevel1);
- //prefsHandler->read(EETH_MAX_ONE, &config->maximumLevel1);
- //prefsHandler->read(EETH_CAR_TYPE, &config->carType);
- } else { //checksum invalid. Reinitialize values and store to EEPROM
- Logger::warn(PIDLISTENER, (char *)Constants::invalidChecksum);
- //config->minimumLevel1 = Throttle1MinValue;
- //config->maximumLevel1 = Throttle1MaxValue;
- //config->carType = Volvo_S80_Gas;
- saveConfiguration();
- }
- //Logger::debug(CANACCELPEDAL, "T1 MIN: %l MAX: %l Type: %d", config->minimumLevel1, config->maximumLevel1, config->carType);
-}
-
-/*
- * Store the current configuration to EEPROM
- */
-void CanPIDListener::saveConfiguration() {
- CanPIDConfiguration *config = (CanPIDConfiguration *) getConfiguration();
-
- Device::saveConfiguration(); // call parent
-
- //prefsHandler->write(EETH_MIN_ONE, config->minimumLevel1);
- //prefsHandler->write(EETH_MAX_ONE, config->maximumLevel1);
- //prefsHandler->write(EETH_CAR_TYPE, config->carType);
- //prefsHandler->saveChecksum();
-}
-
diff --git a/CanThrottle.cpp b/CanThrottle.cpp
index 6545730..74433a6 100644
--- a/CanThrottle.cpp
+++ b/CanThrottle.cpp
@@ -1,197 +1,258 @@
/*
* CanThrottle.cpp
*
-Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
-
-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.
+ Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
+
+ 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 "CanThrottle.h"
-CanThrottle::CanThrottle() : Throttle() {
- prefsHandler = new PrefHandler(CANACCELPEDAL);
- rawSignal.input1 = 0;
- rawSignal.input2 = 0;
- rawSignal.input3 = 0;
- ticksNoResponse = 255; // invalidate input signal until response is received
- responseId = 0;
- responseMask = 0x7ff;
- responseExtended = false;
-
- commonName = "CANBus accelerator";
+CanThrottle::CanThrottle() : Throttle()
+{
+ prefsHandler = new PrefHandler(CANACCELPEDAL);
+ rawSignal.input1 = 0;
+ rawSignal.input2 = 0;
+ rawSignal.input3 = 0;
+ ticksNoResponse = 255; // invalidate input signal until response is received
+ responseId = 0;
+ responseMask = 0x7ff;
+ responseExtended = false;
+
+ commonName = "CANBus accelerator";
}
-void CanThrottle::setup() {
- TickHandler::getInstance()->detach(this);
-
- Logger::info("add device: CanThrottle (id: %X, %X)", CANACCELPEDAL, this);
-
- loadConfiguration();
- Throttle::setup();
-
- requestFrame.length = 0x08;
- requestFrame.rtr = 0x00;
- requestFrame.extended = 0x00;
-
- CanThrottleConfiguration *config = (CanThrottleConfiguration *)getConfiguration();
- switch (config->carType) {
- case Volvo_S80_Gas:
- // Request: dlc=0x08 fid=0x7e0 id=0x7e0 ide=0x00 rtr=0x00 data=0x03,0x22,0xEE,0xCB,0x00,0x00,0x00,0x00 (vida: [0x00, 0x00, 0x07, 0xe0, 0x22, 0xee, 0xcb])
- // Raw response: dlc=0x08 fid=0x7e8 id=0x7e8 ide=0x00 rtr=0x00 data=0x04,0x62,0xEE,0xCB,0x14,0x00,0x00,0x00 (vida: [0x00, 0x00, 0x07, 0xe8, 0x62, 0xee, 0xcb, 0x14])
- requestFrame.id = 0x7e0;
- memcpy(requestFrame.data.bytes, (const uint8_t[]){ 0x03, 0x22, 0xee, 0xcb, 0x00, 0x00, 0x00, 0x00 }, 8);
- responseId = 0x7e8;
- break;
- case Volvo_V50_Diesel:
- // Request: dlc=0x08 fid=0xFFFFE id=0x3FFFE ide=0x01 rtr=0x00 data=0xCD,0x11,0xA6,0x00,0x24,0x01,0x00,0x00 ([0x00, 0xf, 0xff, 0xfe, 0xcd, 0x11, 0xa6, 0x00, 0x24, 0x01, 0x00, 0x00])
- // Response: dlc=0x08 fid=0x400021 id=0x21 ide=0x01 rtr=0x00 data=0xCE,0x11,0xE6,0x00,0x24,0x03,0xFD,0x00 (vida: [0x00, 0x40, 0x00, 0x21, 0xce, 0x11, 0xe6, 0x00, 0x24, 0x03, 0xfd, 0x00])
- requestFrame.id = 0x3FFFE;
- requestFrame.extended = 0x01;
- memcpy(requestFrame.data.bytes, (const uint8_t[]){ 0xce, 0x11, 0xe6, 0x00, 0x24, 0x03, 0xfd, 0x00 }, 8);
- responseId = 0x21;
- responseExtended = true;
- break;
- default:
- Logger::error(CANACCELPEDAL, "no valid car type defined.");
- }
-
- CanHandler::getInstanceCar()->attach(this, responseId, responseMask, responseExtended);
- TickHandler::getInstance()->attach(this, CFG_TICK_INTERVAL_CAN_THROTTLE);
+void CanThrottle::setup()
+{
+ Throttle::setup();
+
+ requestFrame.length = 0x08;
+ requestFrame.rtr = 0x00;
+ requestFrame.extended = 0x00;
+
+ SystemIOConfiguration *config = (SystemIOConfiguration *) systemIO.getConfiguration();
+
+ switch (config->carType) {
+ case SystemIOConfiguration::OBD2:
+ requestFrame.id = 0x7df; // OBD2 broadcast (or specific address from 0x7e0 to 0x7e7)
+ memcpy(requestFrame.data.bytes, (const uint8_t[] ) { 0x02, 0x01, 0x4c, 0x00, 0x00, 0x00, 0x00, 0x00 }, 8); // 2=data bytes, 1=current data, 4c=throttle commanded
+ responseId = 0x7e8; // usually ECU responds on 0x7e8 (possible range: 0x7e8 to 0x7ef)
+ ready = true;
+ break;
+ case SystemIOConfiguration::Volvo_S80_Gas:
+ // Request: dlc=0x08 fid=0x7e0 id=0x7e0 ide=0x00 rtr=0x00 data=0x03,0x22,0xEE,0xCB,0x00,0x00,0x00,0x00 (vida: [0x00, 0x00, 0x07, 0xe0, 0x22, 0xee, 0xcb])
+ // Raw response: dlc=0x08 fid=0x7e8 id=0x7e8 ide=0x00 rtr=0x00 data=0x04,0x62,0xEE,0xCB,0x14,0x00,0x00,0x00 (vida: [0x00, 0x00, 0x07, 0xe8, 0x62, 0xee, 0xcb, 0x14])
+ requestFrame.id = 0x7e0;
+ memcpy(requestFrame.data.bytes, (const uint8_t[] ) { 0x03, 0x22, 0xee, 0xcb, 0x00, 0x00, 0x00, 0x00 }, 8);
+ responseId = 0x7e8;
+ ready = true;
+ break;
+
+ case SystemIOConfiguration::Volvo_V50_Diesel:
+ // Request: dlc=0x08 fid=0xFFFFE id=0x3FFFE ide=0x01 rtr=0x00 data=0xCD,0x11,0xA6,0x00,0x24,0x01,0x00,0x00 (vida: [0x00, 0xf, 0xff, 0xfe, 0xcd, 0x11, 0xa6, 0x00, 0x24, 0x01, 0x00, 0x00])
+ // Response: dlc=0x08 fid=0x400021 id=0x21 ide=0x01 rtr=0x00 data=0xCE,0x11,0xE6,0x00,0x24,0x03,0xFD,0x00 (vida: [0x00, 0x40, 0x00, 0x21, 0xce, 0x11, 0xe6, 0x00, 0x24, 0x03, 0xfd, 0x00])
+ requestFrame.id = 0x3FFFE;
+ requestFrame.extended = 0x01;
+ memcpy(requestFrame.data.bytes, (const uint8_t[] ) { 0xce, 0x11, 0xe6, 0x00, 0x24, 0x03, 0xfd, 0x00 }, 8);
+ responseId = 0x21;
+ responseExtended = true;
+ ready = true;
+ break;
+
+ default:
+ logger.error(this, "no valid car type defined.");
+ }
+}
+
+/**
+ * Tear down the device in a safe way.
+ */
+void CanThrottle::tearDown()
+{
+ Throttle::tearDown();
+
+ canHandlerCar.detach(this, responseId, responseMask);
+}
+
+/**
+ * act on messages the super-class does not react upon, like state change
+ * to ready or running which should enable/disable the controller
+ */
+void CanThrottle::handleStateChange(Status::SystemState oldState, Status::SystemState newState)
+{
+ Throttle::handleStateChange(oldState, newState);
+
+ if (newState == Status::ready || newState == Status::running) {
+ if (oldState != Status::ready && oldState != Status::running) {
+ canHandlerCar.attach(this, responseId, responseMask, responseExtended);
+ tickHandler.attach(this, CFG_TICK_INTERVAL_CAN_THROTTLE);
+ }
+ } else {
+ if (oldState == Status::ready || oldState == Status::running) {
+ tearDown();
+ }
+ }
}
/*
* Send a request to the ECU.
*
*/
-void CanThrottle::handleTick() {
- Throttle::handleTick(); // Call parent handleTick
+void CanThrottle::handleTick()
+{
+ Throttle::handleTick(); // Call parent handleTick
- CanHandler::getInstanceCar()->sendFrame(requestFrame);
+ canHandlerCar.sendFrame(requestFrame);
- if (ticksNoResponse < 255) // make sure it doesn't overflow
- ticksNoResponse++;
+ if (ticksNoResponse < 255) { // make sure it doesn't overflow
+ ticksNoResponse++;
+ }
}
/*
* Handle the response of the ECU and calculate the throttle value
*
*/
-void CanThrottle::handleCanFrame(CAN_FRAME *frame) {
- CanThrottleConfiguration *config = (CanThrottleConfiguration *)getConfiguration();
-
- if (frame->id == responseId) {
- switch (config->carType) {
- case Volvo_S80_Gas:
- rawSignal.input1 = frame->data.bytes[4];
- break;
- case Volvo_V50_Diesel:
- rawSignal.input1 = (frame->data.bytes[5] + 1) * frame->data.bytes[6];
- break;
- }
- ticksNoResponse = 0;
- }
+void CanThrottle::handleCanFrame(CAN_FRAME *frame)
+{
+ SystemIOConfiguration *config = (SystemIOConfiguration *) systemIO.getConfiguration();
+
+ if (frame->id == responseId) {
+ switch (config->carType) {
+ case SystemIOConfiguration::OBD2:
+ if (frame->data.bytes[0] == 0x3 && frame->data.bytes[1] == 0x41 && frame->data.bytes[2] == 0x4c) { // [0]=num data bytes, [1]=mode + 0x40, [2]=PID
+ rawSignal.input1 = frame->data.bytes[3];
+ ticksNoResponse = 0;
+ }
+ break;
+ case SystemIOConfiguration::Volvo_S80_Gas:
+ // only evaluate messages with payload 0x04,0x62,0xEE,0xCB as other ECU data is also sent by with 0x738
+ if (frame->data.bytes[0] == 0x04 && frame->data.bytes[1] == 0x62 && frame->data.bytes[2] == 0xee && frame->data.bytes[3] == 0xcb) {
+ rawSignal.input1 = frame->data.bytes[4];
+ ticksNoResponse = 0;
+ }
+ break;
+
+ case SystemIOConfiguration::Volvo_V50_Diesel:
+ // only evaluate messages with payload 0xCE,0x11,0xE6,0x00,0x2
+ if (frame->data.bytes[0] == 0xce && frame->data.bytes[1] == 0x11 && frame->data.bytes[2] == 0x6E && frame->data.bytes[3] == 0x00
+ && frame->data.bytes[4] == 0x02) {
+ rawSignal.input1 = (frame->data.bytes[5] + 1) * frame->data.bytes[6];
+ ticksNoResponse = 0;
+ }
+ break;
+ }
+ }
}
-RawSignalData* CanThrottle::acquireRawSignal() {
- return &rawSignal; // should have already happened in the background
+RawSignalData* CanThrottle::acquireRawSignal()
+{
+ return &rawSignal; // should have already happened in the background
}
-bool CanThrottle::validateSignal(RawSignalData* rawSignal) {
- CanThrottleConfiguration *config = (CanThrottleConfiguration *) getConfiguration();
-
- if (ticksNoResponse >= CFG_CANTHROTTLE_MAX_NUM_LOST_MSG) {
- if (status == OK)
- Logger::error(CANACCELPEDAL, "no response on position request received: %d ", ticksNoResponse);
- status = ERR_MISC;
- return false;
- }
- if (rawSignal->input1 > (config->maximumLevel1 + CFG_THROTTLE_TOLERANCE)) {
- if (status == OK)
- Logger::error(CANACCELPEDAL, (char *)Constants::valueOutOfRange, rawSignal->input1);
- status = ERR_HIGH_T1;
- return false;
- }
- if (rawSignal->input1 < (config->minimumLevel1 - CFG_THROTTLE_TOLERANCE)) {
- if (status == OK)
- Logger::error(CANACCELPEDAL, (char *)Constants::valueOutOfRange, rawSignal->input1);
- status = ERR_LOW_T1;
- return false;
- }
-
- // all checks passed -> throttle seems to be ok
- if (status != OK)
- Logger::info(CANACCELPEDAL, (char *)Constants::normalOperation);
- status = OK;
- return true;
+bool CanThrottle::validateSignal(RawSignalData* rawSignal)
+{
+ CanThrottleConfiguration *config = (CanThrottleConfiguration *) getConfiguration();
+
+ if (ticksNoResponse >= CFG_CANTHROTTLE_MAX_NUM_LOST_MSG) {
+ if (throttleStatus == OK) {
+ logger.error(this, "no response on position request received: %d ", ticksNoResponse);
+ }
+
+ throttleStatus = ERR_MISC;
+ return false;
+ }
+
+ if (rawSignal->input1 > (config->maximumLevel + CFG_THROTTLE_TOLERANCE)) {
+ if (throttleStatus == OK) {
+ logger.error(this, VALUE_OUT_OF_RANGE, rawSignal->input1);
+ }
+
+ throttleStatus = ERR_HIGH_T1;
+ return false;
+ }
+
+ if (rawSignal->input1 < (config->minimumLevel - CFG_THROTTLE_TOLERANCE)) {
+ if (throttleStatus == OK) {
+ logger.error(this, VALUE_OUT_OF_RANGE, rawSignal->input1);
+ }
+
+ throttleStatus = ERR_LOW_T1;
+ return false;
+ }
+
+ // all checks passed -> throttle seems to be ok
+ if (throttleStatus != OK) {
+ logger.info(this, NORMAL_OPERATION);
+ }
+
+ throttleStatus = OK;
+ return true;
}
-uint16_t CanThrottle::calculatePedalPosition(RawSignalData* rawSignal) {
- CanThrottleConfiguration *config = (CanThrottleConfiguration *) getConfiguration();
+uint16_t CanThrottle::calculatePedalPosition(RawSignalData* rawSignal)
+{
+ CanThrottleConfiguration *config = (CanThrottleConfiguration *) getConfiguration();
- return normalizeAndConstrainInput(rawSignal->input1, config->minimumLevel1, config->maximumLevel1);
+ return normalizeAndConstrainInput(rawSignal->input1, config->minimumLevel, config->maximumLevel);
}
-DeviceId CanThrottle::getId() {
- return CANACCELPEDAL;
+DeviceId CanThrottle::getId()
+{
+ return CANACCELPEDAL;
}
-void CanThrottle::loadConfiguration() {
- CanThrottleConfiguration *config = (CanThrottleConfiguration *) getConfiguration();
+void CanThrottle::loadConfiguration()
+{
+ CanThrottleConfiguration *config = (CanThrottleConfiguration *) getConfiguration();
- if (!config) { // as lowest sub-class make sure we have a config object
- config = new CanThrottleConfiguration();
- setConfiguration(config);
- }
+ if (!config) { // as lowest sub-class make sure we have a config object
+ config = new CanThrottleConfiguration();
+ setConfiguration(config);
+ }
- Throttle::loadConfiguration(); // call parent
+ Throttle::loadConfiguration(); // call parent
#ifdef USE_HARD_CODED
- if (false) {
+
+ if (false) {
#else
- if (prefsHandler->checksumValid()) { //checksum is good, read in the values stored in EEPROM
+
+ if (prefsHandler->checksumValid()) { //checksum is good, read in the values stored in EEPROM
#endif
- Logger::debug(CANACCELPEDAL, (char *)Constants::validChecksum);
- prefsHandler->read(EETH_MIN_ONE, &config->minimumLevel1);
- prefsHandler->read(EETH_MAX_ONE, &config->maximumLevel1);
- prefsHandler->read(EETH_CAR_TYPE, &config->carType);
- } else { //checksum invalid. Reinitialize values and store to EEPROM
- Logger::warn(CANACCELPEDAL, (char *)Constants::invalidChecksum);
- config->minimumLevel1 = Throttle1MinValue;
- config->maximumLevel1 = Throttle1MaxValue;
- config->carType = Volvo_S80_Gas;
- saveConfiguration();
- }
- Logger::debug(CANACCELPEDAL, "T1 MIN: %l MAX: %l Type: %d", config->minimumLevel1, config->maximumLevel1, config->carType);
+ } else {
+ saveConfiguration();
+ }
+
+ logger.info(this, "MIN: %ld MAX: %ld", config->minimumLevel, config->maximumLevel);
}
/*
* Store the current configuration to EEPROM
*/
-void CanThrottle::saveConfiguration() {
- CanThrottleConfiguration *config = (CanThrottleConfiguration *) getConfiguration();
+void CanThrottle::saveConfiguration()
+{
+ CanThrottleConfiguration *config = (CanThrottleConfiguration *) getConfiguration();
- Throttle::saveConfiguration(); // call parent
+ Throttle::saveConfiguration(); // call parent
- prefsHandler->write(EETH_MIN_ONE, config->minimumLevel1);
- prefsHandler->write(EETH_MAX_ONE, config->maximumLevel1);
- prefsHandler->write(EETH_CAR_TYPE, config->carType);
- prefsHandler->saveChecksum();
+ prefsHandler->saveChecksum();
}
diff --git a/CanThrottle.h b/CanThrottle.h
index be98e14..a3ffbda 100644
--- a/CanThrottle.h
+++ b/CanThrottle.h
@@ -32,44 +32,39 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
#include "Throttle.h"
#include "TickHandler.h"
#include "CanHandler.h"
-#include "constants.h"
#include "DeviceManager.h"
-enum CanCarType {
- unknowkn = 0x00,
- Volvo_S80_Gas = 0x01,
- Volvo_V50_Diesel = 0x02
-};
-
-class CanThrottleConfiguration : public ThrottleConfiguration {
+class CanThrottleConfiguration : public ThrottleConfiguration
+{
public:
- uint16_t minimumLevel1, maximumLevel1; // values for when the pedal is at its min and max
- uint16_t carType; // the type of car, so we know how to interpret which bytes
};
-class CanThrottle: public Throttle, CanObserver {
+class CanThrottle: public Throttle, CanObserver
+{
public:
- CanThrottle();
- void setup();
- void handleTick();
- void handleCanFrame(CAN_FRAME *frame);
- DeviceId getId();
+ CanThrottle();
+ void setup();
+ void tearDown();
+ void handleTick();
+ void handleStateChange(Status::SystemState, Status::SystemState);
+ void handleCanFrame(CAN_FRAME *frame);
+ DeviceId getId();
- RawSignalData *acquireRawSignal();
- void loadConfiguration();
- void saveConfiguration();
+ RawSignalData *acquireRawSignal();
+ void loadConfiguration();
+ void saveConfiguration();
protected:
- bool validateSignal(RawSignalData *);
- uint16_t calculatePedalPosition(RawSignalData *);
+ bool validateSignal(RawSignalData *);
+ uint16_t calculatePedalPosition(RawSignalData *);
private:
- CAN_FRAME requestFrame; // the request frame sent to the car
- RawSignalData rawSignal; // raw signal
- uint8_t ticksNoResponse; // number of ticks no response was received
- uint32_t responseId; // the CAN id with which the response is sent;
- uint32_t responseMask; // the mask for the responseId
- bool responseExtended; // if the response is expected as an extended frame
+ CAN_FRAME requestFrame; // the request frame sent to the car
+ RawSignalData rawSignal; // raw signal
+ uint8_t ticksNoResponse; // number of ticks no response was received
+ uint32_t responseId; // the CAN id with which the response is sent;
+ uint32_t responseMask; // the mask for the responseId
+ bool responseExtended; // if the response is expected as an extended frame
};
#endif /* CAN_THROTTLE_H_ */
diff --git a/Charger.cpp b/Charger.cpp
new file mode 100644
index 0000000..6713e4c
--- /dev/null
+++ b/Charger.cpp
@@ -0,0 +1,364 @@
+/*
+ * Charger.cpp
+ *
+ * Parent class for all chargers
+ *
+Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
+
+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 "Charger.h"
+
+Charger::Charger() : Device()
+{
+ inputCurrent = 0;
+ inputVoltage = 0;
+ batteryVoltage = 0;
+ batteryCurrent = 0;
+ temperature = 0;
+ ampereMilliSeconds = 0;
+ chargeStartTime = 0;
+ requestedOutputCurrent = 0;
+ inputCurrentTarget = 0xffff;
+ maximumInputCurrent = 0;
+ inputVoltageStart = 0xffff;
+ lastTick = 0;
+}
+
+Charger::~Charger()
+{
+}
+
+/*
+ * Process event from the tick handler.
+ */
+void Charger::handleTick()
+{
+ Device::handleTick(); // call parent
+
+ uint32_t timeStamp = millis();
+ ampereMilliSeconds += (timeStamp - lastTick) * batteryCurrent;
+ lastTick = timeStamp;
+}
+
+/**
+ * Act on messages the super-class does not react upon, like state change
+ * to charging which should enable the charger
+ */
+void Charger::handleStateChange(Status::SystemState oldState, Status::SystemState newState)
+{
+ Device::handleStateChange(oldState, newState);
+ if (newState == Status::charging || newState == Status::batteryHeating) {
+ ChargerConfiguration *config = (ChargerConfiguration *) getConfiguration();
+
+ // re-initialize variables
+ inputCurrent = 0;
+ inputVoltage = 0;
+ batteryVoltage = 0;
+ batteryCurrent = 0;
+ ampereMilliSeconds = 0;
+ inputCurrentTarget = (config->initialInputCurrent > 0 ? config->initialInputCurrent : 0xffff); // if 0xffff must be overridden via wifi to get enabled during charge
+ maximumInputCurrent = 0;
+ inputVoltageStart = 0xffff;
+ chargeStartTime = millis();
+ lastTick = millis();
+
+ requestedOutputCurrent = config->constantCurrent;
+ powerOn = true;
+ } else {
+ if (powerOn) {
+ logger.info(this, "Charging finished after %d min, %.2f Ah", (millis() - chargeStartTime) / 60000, (float) ampereMilliSeconds / 360000000.0f);
+ }
+ requestedOutputCurrent = 0;
+ powerOn = false;
+ }
+ systemIO.setEnableCharger(powerOn);
+}
+
+/**
+ * Calculate desired output voltage to battery in 0.1V
+ */
+uint16_t Charger::calculateOutputVoltage()
+{
+ if (powerOn && running) {
+ ChargerConfiguration *config = (ChargerConfiguration *) getConfiguration();
+ return config->constantVoltage;
+ }
+ return 0;
+}
+
+/**
+ * Based on the current SOC, battery capacity and charge current reported by the BMS the remaining
+ * time to fully charge the battery is calculated (Note: tapering down at end of charge is not reflected)
+ * Formula: remaining Ah to charge = Pack remaining Ah * (100 - SOC) / SOC
+ * remaining minutes = remaining Ah / charge Amps * 60
+ */
+uint16_t Charger::calculateTimeRemaining()
+{
+ BatteryManager *batteryManager = deviceManager.getBatteryManager();
+
+ if (batteryManager && batteryManager->hasSoc() && batteryManager->hasAmpHours() && batteryCurrent != 0 && batteryManager->getSoc() != 0) {
+ return batteryManager->getAmpHours() * (200 - batteryManager->getSoc()) / batteryManager->getSoc() * 600 / batteryCurrent;
+ }
+ return 0;
+}
+
+/**
+ * Calculate desired output current to battery in 0.1A
+ */
+uint16_t Charger::calculateOutputCurrent()
+{
+ BatteryManager *batteryManager = deviceManager.getBatteryManager();
+
+ if (powerOn && running &&
+ (!batteryManager || !batteryManager->hasChargerEnabled() || batteryManager->isChargerEnabled())) {
+ ChargerConfiguration *config = (ChargerConfiguration *) getConfiguration();
+ int16_t temperature;
+
+//TODO inmplement temp hysterese / derating according to the following config variables:
+// bool useTemperatureDerating; // if true derating is used at high temperatures, otherwise hysterese at fixed temperatures will be used
+// uint16_t deratingTemperature; // 0.1Ah per deg Celsius
+// uint16_t deratingReferenceTemperature; // 0.1 deg Celsius where derating will reach 0 Amp
+// uint16_t hystereseStopTemperature; // 0.1 deg Celsius where charging will stop in hysterese mode
+// uint16_t hystereseResumeTemperature; // 0.1 deg Celsius where charging is resumed
+
+ // in constant voltage phase decrease current accordingly
+ if (batteryVoltage > config->constantVoltage && requestedOutputCurrent > 0) {
+ requestedOutputCurrent--;
+ }
+ if (batteryManager) {
+ if (batteryManager->hasChargeLimit()) {
+ uint16_t chargeLimit = batteryManager->getChargeLimit() * 10;
+ if (chargeLimit > requestedOutputCurrent) {
+ requestedOutputCurrent++; // only increase in small steps (0.1A per 100ms) to reduce fluctuations
+ }
+ if (chargeLimit < requestedOutputCurrent) {
+ requestedOutputCurrent = chargeLimit; // don't allow it to fluctuate up and down, stay down
+ }
+ } else if (batteryManager->hasAllowCharging() && !batteryManager->isChargeAllowed()) {
+ requestedOutputCurrent = 0;
+ logger.info(this, "BMS terminated charging");
+ }
+ }
+ if (requestedOutputCurrent < config->terminateCurrent ||
+ ((millis() - chargeStartTime) > 5000 && batteryCurrent < config->terminateCurrent)) { // give the charger 5sec to ramp up the current
+ requestedOutputCurrent = 0;
+ logger.info(this, "Reached end of normal charge cycle");
+ status.setSystemState(Status::charged);
+ }
+ if ((millis() - chargeStartTime) > (uint32_t) config->maximumChargeTime * 60000) {
+ requestedOutputCurrent = 0;
+ logger.error(this, "Maximum charge time exceeded (%dmin)", (millis() - chargeStartTime) / 60000);
+ status.setSystemState(Status::error);
+ }
+ if (batteryVoltage > config->maximumBatteryVoltage) {
+ requestedOutputCurrent = 0;
+ logger.error(this, "Maximum battery voltage exceeded (%.1fV)", (float) batteryVoltage / 10.0f);
+ status.setSystemState(Status::error);
+ }
+ if ((batteryVoltage < config->minimumBatteryVoltage) && (millis() - chargeStartTime) > 5000) {
+ requestedOutputCurrent = 0;
+ logger.error(this, "Battery voltage too low (%.1fV)", (float) batteryVoltage / 10.0f);
+ status.setSystemState(Status::error);
+ }
+ if (ampereMilliSeconds / 36000000 > config->maximumAmpereHours) {
+ requestedOutputCurrent = 0;
+ logger.error(this, "Maximum ampere hours exceeded (%.2f)", (float) ampereMilliSeconds / 360000000.0f);
+ status.setSystemState(Status::error);
+ }
+ temperature = status.getHighestBatteryTemperature();
+ if (temperature != CFG_NO_TEMPERATURE_DATA && temperature > config->maximumTemperature) {
+ requestedOutputCurrent = 0;
+ logger.error(this, "Battery temperature too high (%.1fC)", (float) temperature / 10.0f);
+ status.setSystemState(Status::error);
+ }
+ temperature = status.getLowestBatteryTemperature();
+ if (temperature != CFG_NO_TEMPERATURE_DATA && temperature < config->minimumTemperature && temperature != 0) {
+ requestedOutputCurrent = 0;
+ logger.warn(this, "Battery temperature too low (%.1fC)", (float) temperature / 10.0f);
+ }
+ return requestedOutputCurrent;
+ }
+ return 0;
+}
+
+/*
+ * Return the device type
+ */
+DeviceType Charger::getType()
+{
+ return (DEVICE_CHARGER);
+}
+
+uint16_t Charger::getBatteryCurrent()
+{
+ return batteryCurrent;
+}
+
+uint16_t Charger::getBatteryVoltage()
+{
+ return batteryVoltage;
+}
+
+uint16_t Charger::getInputCurrent()
+{
+ return inputCurrent;
+}
+
+uint16_t Charger::getInputVoltage()
+{
+ return inputVoltage;
+}
+
+int16_t Charger::getTemperature()
+{
+ return temperature;
+}
+
+void Charger::setInputCurrentTarget(uint16_t current) {
+ if (current > maximumInputCurrent) {
+ current = maximumInputCurrent;
+ logger.info("Current limited to %.1fA due to power line safety", current / 10.0f);
+ }
+ inputCurrentTarget = current;
+ logger.debug(this, "input current target: %.1f", inputCurrentTarget / 10.0f);
+}
+
+uint16_t Charger::calculateMaximumInputCurrent()
+{
+ ChargerConfiguration *config = (ChargerConfiguration *) getConfiguration();
+
+ // start with a low current (e.g. 2A) during first couple of seconds to measure base line voltage
+ if (chargeStartTime + config->measureTime > millis()) {
+ if (inputVoltage != 0) {
+ inputVoltageStart = (inputVoltageStart == 0xffff ? inputVoltage : (inputVoltageStart + inputVoltage) / 2);
+ }
+ return config->measureCurrent;
+ }
+
+ uint16_t maxTargetCurrent = (inputCurrentTarget != 0xffff ? min(inputCurrentTarget, config->maximumInputCurrent) : config->maximumInputCurrent);
+
+ // if input voltage drop is less than e.g. 3%, increase up to maxTargetCurrent, otherwise protect input line from over-heating
+ if (inputVoltageStart - inputVoltage < inputVoltageStart / config->voltageDrop) {
+ maximumInputCurrent++;
+ }
+
+ return min(maxTargetCurrent, maximumInputCurrent);
+}
+
+/*
+ * Load configuration data from EEPROM.
+ *
+ * If not available or the checksum is invalid, default values are chosen.
+ */
+void Charger::loadConfiguration()
+{
+ ChargerConfiguration *config = (ChargerConfiguration *) getConfiguration();
+
+ if (!config) {
+ config = new ChargerConfiguration();
+ setConfiguration(config);
+ }
+
+ Device::loadConfiguration(); // call parent
+ logger.info(this, "Charger configuration:");
+
+#ifdef USE_HARD_CODED
+
+ if (false) {
+#else
+ if (prefsHandler->checksumValid()) { //checksum is good, read in the values stored in EEPROM
+#endif
+ prefsHandler->read(EECH_MAX_INPUT_CURRENT, &config->maximumInputCurrent);
+ prefsHandler->read(EECH_INITIAL_INPUT_CURRENT, &config->initialInputCurrent);
+ prefsHandler->read(EECH_CONSTANT_CURRENT, &config->constantCurrent);
+ prefsHandler->read(EECH_CONSTANT_VOLTAGE, &config->constantVoltage);
+ prefsHandler->read(EECH_TERMINATE_CURRENT, &config->terminateCurrent);
+ prefsHandler->read(EECH_MIN_BATTERY_VOLTAGE, &config->minimumBatteryVoltage);
+ prefsHandler->read(EECH_MAX_BATTERY_VOLTAGE, &config->maximumBatteryVoltage);
+ prefsHandler->read(EECH_MIN_BATTERY_TEMPERATURE, (uint16_t *) &config->minimumTemperature);
+ prefsHandler->read(EECH_MAX_BATTERY_TEMPERATURE, &config->maximumTemperature);
+ prefsHandler->read(EECH_MAX_AMPERE_HOURS, &config->maximumAmpereHours);
+ prefsHandler->read(EECH_MAX_CHARGE_TIME, &config->maximumChargeTime);
+ prefsHandler->read(EECH_DERATING_TEMPERATURE, &config->deratingRate);
+ prefsHandler->read(EECH_DERATING_REFERENCE, &config->deratingReferenceTemperature);
+ prefsHandler->read(EECH_HYSTERESE_STOP, &config->hystereseStopTemperature);
+ prefsHandler->read(EECH_HYSTERESE_RESUME, &config->hystereseResumeTemperature);
+ prefsHandler->read(EECH_MEASURE_TIME, &config->measureTime);
+ prefsHandler->read(EECH_MEASURE_CURRENT, &config->measureCurrent);
+ prefsHandler->read(EECH_VOLTAGE_DROP, &config->voltageDrop);
+ } else { //checksum invalid. Reinitialize values and store to EEPROM
+ config->maximumInputCurrent = 100;
+ config->initialInputCurrent = 0;
+ config->constantCurrent = 100;
+ config->constantVoltage = 4165;
+ config->terminateCurrent = 50;
+ config->minimumBatteryVoltage = 3272;
+ config->maximumBatteryVoltage = 4284;
+ config->minimumTemperature = 30;
+ config->maximumTemperature = 600;
+ config->maximumAmpereHours = 1200;
+ config->maximumChargeTime = 600;
+ config->deratingRate = 1;
+ config->deratingReferenceTemperature = 500;
+ config->hystereseStopTemperature = 600;
+ config->hystereseResumeTemperature = 500;
+ config->measureTime = 5000;
+ config->measureCurrent = 20;
+ config->voltageDrop = 33;
+ saveConfiguration();
+ }
+
+ logger.info(this, "max input current: %.1fA, constant current: %.1fA, constant voltage: %.1fV", (float) config->maximumInputCurrent / 10.0F, (float) config->constantCurrent / 10.0F, (float) config->constantVoltage / 10.0F);
+ logger.info(this, "terminate current: %.1fA, battery min: %.1fV max: %.1fV, initial input current: %.1fA", (float) config->terminateCurrent / 10.0F, (float) config->minimumBatteryVoltage / 10.0F, (float) config->maximumBatteryVoltage / 10.0F, config->initialInputCurrent / 10.0f);
+}
+
+/*
+ * Store the current configuration parameters to EEPROM.
+ */
+void Charger::saveConfiguration()
+{
+ ChargerConfiguration *config = (ChargerConfiguration *) getConfiguration();
+
+ Device::saveConfiguration(); // call parent
+
+ prefsHandler->write(EECH_MAX_INPUT_CURRENT, config->maximumInputCurrent);
+ prefsHandler->write(EECH_INITIAL_INPUT_CURRENT, config->initialInputCurrent);
+ prefsHandler->write(EECH_CONSTANT_CURRENT, config->constantCurrent);
+ prefsHandler->write(EECH_CONSTANT_VOLTAGE, config->constantVoltage);
+ prefsHandler->write(EECH_TERMINATE_CURRENT, config->terminateCurrent);
+ prefsHandler->write(EECH_MIN_BATTERY_VOLTAGE, config->minimumBatteryVoltage);
+ prefsHandler->write(EECH_MAX_BATTERY_VOLTAGE, config->maximumBatteryVoltage);
+ prefsHandler->write(EECH_MIN_BATTERY_TEMPERATURE, (uint16_t) config->minimumTemperature);
+ prefsHandler->write(EECH_MAX_BATTERY_TEMPERATURE, config->maximumTemperature);
+ prefsHandler->write(EECH_MAX_AMPERE_HOURS, config->maximumAmpereHours);
+ prefsHandler->write(EECH_MAX_CHARGE_TIME, config->maximumChargeTime);
+ prefsHandler->write(EECH_DERATING_TEMPERATURE, config->deratingRate);
+ prefsHandler->write(EECH_DERATING_REFERENCE, config->deratingReferenceTemperature);
+ prefsHandler->write(EECH_HYSTERESE_STOP, config->hystereseStopTemperature);
+ prefsHandler->write(EECH_HYSTERESE_RESUME, config->hystereseResumeTemperature);
+ prefsHandler->write(EECH_MEASURE_TIME, config->measureTime);
+ prefsHandler->write(EECH_MEASURE_CURRENT, config->measureCurrent);
+ prefsHandler->write(EECH_VOLTAGE_DROP, config->voltageDrop);
+
+ prefsHandler->saveChecksum();
+}
diff --git a/Charger.h b/Charger.h
new file mode 100644
index 0000000..9bf07d3
--- /dev/null
+++ b/Charger.h
@@ -0,0 +1,102 @@
+/*
+ * Charger.h
+ *
+ * Parent class for chargers
+ *
+Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
+
+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 CHARGER_H_
+#define CHARGER_H_
+
+#include
+#include "config.h"
+#include "DeviceManager.h"
+
+class ChargerConfiguration : public DeviceConfiguration
+{
+public:
+ uint16_t maximumInputCurrent; // maximum input current in 0.1A (e.g. from 230V mains)
+ uint16_t initialInputCurrent; // initial setting for max input current in 0.1A - 0=disable (e.g. to start with 8A and not with 16A)
+ uint16_t constantCurrent; // current in 0.1A during constant current phase
+ uint16_t constantVoltage; // voltage in 0.1V during constant voltage phase and point where switching from constant current to constant voltage
+ uint16_t terminateCurrent; // current in 0.1A at which to terminate the charge process
+
+ uint16_t minimumBatteryVoltage; // minimum battery voltage in 0.1V where to start the charge process
+ uint16_t maximumBatteryVoltage; // maximum battery voltage in 0.1V - if exceeded, the charge process will terminate
+ int16_t minimumTemperature; // temperature in 0.1 deg Celsius below which charging will not occur
+ uint16_t maximumTemperature; // temperature in 0.1 deg Celsius where charging is terminated
+ uint16_t maximumAmpereHours; // charge in 0.1 Ah where charging is terminated
+ uint16_t maximumChargeTime; // charge time in 1 minutes at which charging is terminated
+
+ uint16_t deratingRate; // 0.1Ah per deg Celsius
+ uint16_t deratingReferenceTemperature; // 0.1 deg Celsius where derating will reach 0 Amp (0=disable)
+ uint16_t hystereseStopTemperature; // 0.1 deg Celsius where charging will stop in hysterese mode (0=disable)
+ uint16_t hystereseResumeTemperature; // 0.1 deg Celsius where charging is resumed
+
+ uint16_t measureTime; // time to measure input voltage at idle in ms
+ uint16_t measureCurrent; // current to apply during input voltage measurement (required by some chargers, e.g. NLG5 needs 2A) in 0.1A
+ uint8_t voltageDrop; // divisor by which the input voltage may drop when current is ramped up (e.g. 33 if it may drop 3%, 230V / 33 = 7V)
+};
+
+class Charger : public Device
+{
+public:
+ Charger();
+ ~Charger();
+ void handleTick();
+ void handleStateChange(Status::SystemState, Status::SystemState);
+ DeviceType getType();
+
+ void loadConfiguration();
+ void saveConfiguration();
+
+ uint16_t getBatteryCurrent();
+ uint16_t getBatteryVoltage();
+ uint16_t getInputCurrent();
+ uint16_t getInputVoltage();
+ int16_t getTemperature();
+ void setInputCurrentTarget(uint16_t current);
+ uint16_t calculateMaximumInputCurrent();
+ uint16_t calculateTimeRemaining();
+
+protected:
+ uint16_t inputCurrent; // the reported input current in 0.01A
+ uint16_t inputVoltage; // the reported input voltage in 0.1V
+ uint16_t batteryVoltage; // the reported battery voltage in 0.1V
+ uint16_t batteryCurrent; // the reported battery current in 0.01A
+ int16_t temperature; // in 0.1 deg C
+ uint32_t chargeStartTime; // timestamp when charging starts in millis
+ uint32_t lastTick; // last time in ms when the handleTick method was called
+ uint16_t calculateOutputVoltage();
+ uint16_t calculateOutputCurrent();
+
+private:
+ uint64_t ampereMilliSeconds; // ampere hours put into the battery in 1 ampere-milliseconds (divide by 3600000 to get Ah)
+ uint16_t requestedOutputCurrent; // calculated current to be delivered by the charger (in 0.1A), use getOutputCurrent() to retrieve this value - never use it directly !!
+ uint16_t inputCurrentTarget; // the target current to be drawn (e.g. from a solar power plant or manually specified in dashboard) (-1 = ignore, in 0.1A)
+ uint16_t maximumInputCurrent; // the calculated maximum input current (limited by config or power line conditions)
+ uint16_t inputVoltageStart; // input voltage with (almost) no load in 0.1V
+};
+
+#endif
diff --git a/CodaMotorController.cpp b/CodaMotorController.cpp
index 648da0e..6c2b357 100644
--- a/CodaMotorController.cpp
+++ b/CodaMotorController.cpp
@@ -2,331 +2,267 @@
* CodaMotorController.cpp
*
* CAN Interface to the Coda flavored UQM Powerphase 100 inverter -
- Handles sending of commands and reception of status frames to drive
- the inverter and thus motor. Endianess is configurable in the firmware
- inside the UQM inverter but default is little endian. This object module * uses little endian format
- - the least significant byte is the first in order with the MSB following.
+ Handles sending of commands and reception of status frames to drive
+ the inverter and thus motor. Endianess is configurable in the firmware
+ inside the UQM inverter but default is little endian. This object module * uses little endian format
+ - the least significant byte is the first in order with the MSB following.
**************NOTE***************
- Ticks are critical for the UQM inverter. A tick value of 10000 in config.h is necessary as the inverter
+ Ticks are critical for the UQM inverter. A tick value of 10000 in config.h is necessary as the inverter
expects a torque command within each 12 millisecond period. Failing to provide it is a bit subtle to catch
- but quite dramatic. The motor will run at speed for about 5 to 7 minutes and then "cough" losing all torque and
- then recovering. Five minutes later, this will repeat. Setting to a very fast value of 10000 seems to cure it NOW.
+ but quite dramatic. The motor will run at speed for about 5 to 7 minutes and then "cough" losing all torque and
+ then recovering. Five minutes later, this will repeat. Setting to a very fast value of 10000 seems to cure it NOW.
As the software grows and the load on the CPU increases, this could show up again.
*
-Copyright (c) 2014 Jack Rickard
-
-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.
+ Copyright (c) 2014 Jack Rickard
+
+ 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 "CodaMotorController.h"
-template inline Print &operator <<(Print &obj, T arg) { obj.print(arg); return obj; }
+//template inline Print &operator <<(Print &obj, T arg) {
+// obj.print(arg);
+// return obj;
+//}
-long mss;
-extern bool runThrottle;
const uint8_t swizzleTable[] = { 0xAA, 0x7F, 0xFE, 0x29, 0x52, 0xA4, 0x9D, 0xEF, 0xB, 0x16, 0x2C, 0x58, 0xB0, 0x60, 0xC0, 1 };
-
-
-CodaMotorController::CodaMotorController() : MotorController()
-{
-
+CodaMotorController::CodaMotorController() : MotorController() {
prefsHandler = new PrefHandler(CODAUQM);
- operationState = ENABLE;
- online = 0;
- activityCount = 0;
- sequence=0;
+ sequence = 0;
commonName = "Coda UQM Powerphase 100 Inverter";
-
}
+void CodaMotorController::setup() {
+ MotorController::setup(); // run the parent class version of this function
-void CodaMotorController::setup()
-{
- TickHandler::getInstance()->detach(this);
-
- Logger::info("add device: CODA UQM (id:%X, %X)", CODAUQM, this);
+ // register ourselves as observer of all 0x20x can frames for UQM
+ canHandlerEv.attach(this, 0x200, 0x7f0, false);
- loadConfiguration();
+ tickHandler.attach(this, CFG_TICK_INTERVAL_MOTOR_CONTROLLER_CODAUQM);
+}
- MotorController::setup(); // run the parent class version of this function
+void CodaMotorController::handleCanFrame(CAN_FRAME *frame) {
+ int invTemp, rotorTemp, statorTemp;
+
+ //TODO: running should only be set to true if the controller reports that its power-stageis up and running.
+ running = true;
+
+ if (logger.isDebug()) {
+ logger.debug(this, "msg: %#02x %#02x %#02x %#02x %#02x %#02x %#02x %#02x %#02x", frame->id, frame->data.bytes[0], frame->data.bytes[1],
+ frame->data.bytes[2], frame->data.bytes[3], frame->data.bytes[4], frame->data.bytes[5], frame->data.bytes[6], frame->data.bytes[7]);
+ }
+
+ switch (frame->id) {
+
+ case 0x209: //Accurate Feedback Message
+ torqueActual = ((((frame->data.bytes[1] * 256) + frame->data.bytes[0]) - 32128));
+ dcVoltage = (((frame->data.bytes[3] * 256) + frame->data.bytes[2]) - 32128);
+ dcCurrent = (((frame->data.bytes[5] * 256) + frame->data.bytes[4]) - 32128);
+ speedActual = abs((((frame->data.bytes[7] * 256) + frame->data.bytes[6]) - 32128) / 2);
+ if (logger.isDebug()) {
+ logger.debug(this, "Actual Torque: %d DC Voltage: %d Amps: %d RPM: %d", torqueActual / 10, dcVoltage / 10, dcCurrent / 10, speedActual);
+ }
+ reportActivity();
+ break;
+
+ case 0x20A: //System Status Message
+ logger.debug(this, "20A System Status Message Received");
+ reportActivity();
+ break;
+
+ case 0x20B: //Emergency Fuel Cutback Message
+ logger.debug(this, "20B Emergency Fuel Cutback Message Received");
+ reportActivity();
+ break;
+
+ case 0x20C: //Reserved Message
+ logger.debug(this, "20C Reserved Message Received");
+ reportActivity();
+ break;
+
+ case 0x20D: //Limited Torque Percentage Message
+ logger.debug(this, "20D Limited Torque Percentage Message Received");
+ reportActivity();
+ break;
+
+ case 0x20E: //Temperature Feedback Message
+ invTemp = frame->data.bytes[2];
+ rotorTemp = frame->data.bytes[3];
+ statorTemp = frame->data.bytes[4];
+ temperatureController = (invTemp - 40) * 10;
+ temperatureMotor = (max(rotorTemp, statorTemp) - 40) * 10;
+ if (logger.isDebug()) {
+ logger.debug(this, "Inverter temp: %d Motor temp: %d", temperatureController, temperatureMotor);
+ }
+ reportActivity();
+ break;
+
+ case 0x20F: //CAN Watchdog Status Message
+ logger.debug(this, "20F CAN Watchdog status error");
+ status.warning = true;
+ running = false;
+ sendCmd2(); //If we get a Watchdog status, we need to respond with Watchdog reset
+ reportActivity();
+ break;
+ }
+}
- // register ourselves as observer of all 0x20x can frames for UQM
- CanHandler::getInstanceEV()->attach(this, 0x200, 0x7f0, false);
-
- operationState=ENABLE;
- selectedGear=DRIVE;
- TickHandler::getInstance()->attach(this, CFG_TICK_INTERVAL_MOTOR_CONTROLLER_CODAUQM);
-
+void CodaMotorController::handleTick() {
+ MotorController::handleTick(); //kick the ball up to papa
+ sendCmd1(); //Send our lone torque command
}
+/*
+ UQM only HAS a single command CAN bus frame - address 0x204 Everything is stuffed into this one frame. It has a 5 byte payload.
-void CodaMotorController::handleCanFrame(CAN_FRAME *frame)
-{
- int RotorTemp, invTemp, StatorTemp;
- int temp;
- online = 1; //if a frame got to here then it passed the filter and must come from UQM
- if (!running) //if we're newly running then cancel faults if necessary.
- {
- faultHandler.cancelOngoingFault(CODAUQM, FAULT_MOTORCTRL_COMM);
- }
- running=true;
- Logger::debug("UQM inverter msg: %X %X %X %X %X %X %X %X %X", frame->id, frame->data.bytes[0],
- frame->data.bytes[1],frame->data.bytes[2],frame->data.bytes[3],frame->data.bytes[4],
- frame->data.bytes[5],frame->data.bytes[6],frame->data.bytes[7]);
-
- switch (frame->id)
- {
-
- case 0x209: //Accurate Feedback Message
-
- torqueActual = ((((frame->data.bytes[1] * 256) + frame->data.bytes[0])-32128)) ;
- dcVoltage = (((frame->data.bytes[3] * 256) + frame->data.bytes[2])-32128);
- if(dcVoltage<1000){dcVoltage=1000;}//Lowest value we can display on dashboard
- dcCurrent = (((frame->data.bytes[5] * 256) + frame->data.bytes[4])-32128);
- speedActual = abs((((frame->data.bytes[7] * 256) + frame->data.bytes[6])-32128)/2);
- Logger::debug("UQM Actual Torque: %d DC Voltage: %d Amps: %d RPM: %d", torqueActual/10,dcVoltage/10,dcCurrent/10,speedActual);
- break;
-
- case 0x20A: //System Status Message
- Logger::debug("UQM inverter 20A System Status Message Received");
- break;
-
-
- case 0x20B: //Emergency Fuel Cutback Message
- Logger::debug("UQM inverter 20B Emergency Fuel Cutback Message Received");
- break;
-
- case 0x20C: //Reserved Message
- Logger::debug("UQM inverter 20C Reserved Message Received");
- break;
-
- case 0x20D: //Limited Torque Percentage Message
- Logger::debug("UQM inverter 20D Limited Torque Percentage Message Received");
- break;
-
- case 0x20E: //Temperature Feedback Message
-
- invTemp = frame->data.bytes[2];
- RotorTemp = frame->data.bytes[3];
- StatorTemp = frame->data.bytes[4];
- temperatureInverter = (invTemp-40)*10;
- if (RotorTemp > StatorTemp) {temperatureMotor = (RotorTemp-40)*10;}
- else {temperatureMotor = (StatorTemp-40)*10;}
- Logger::debug("UQM 20E Inverter temp: %d Motor temp: %d", temperatureInverter,temperatureMotor);
- break;
-
- case 0x20F: //CAN Watchdog Status Message
- Logger::debug("UQM 20F CAN Watchdog status error");
- warning=true;
- running=false;
- sendCmd2(); //If we get a Watchdog status, we need to respond with Watchdog reset
- break;
- }
-}
+ Byte 1 - always set to 0
+ Byte 2 - Command Byte
+ Left four bits contain enable disable and forward reverse
+ Bits 7/6 DISABLED =01
+ Bits 7/6 ENABLE =10
+ Bits 5/4 REVERSE=01
+ Bits 5/4 FORWARD=10
+ Example: Enabled and Forward: 1010
+ Right four bits (3 to 0) is a sequence counter that counts 0000 to 0111 and back to 0000
-void CodaMotorController::handleTick() {
+ Byte 3 LSB of Torque command value.
- MotorController::handleTick(); //kick the ball up to papa
- sendCmd1(); //Send our lone torque command
- if (millis()-mss>2000 && online==0)
- {
- running=false; // We haven't received any UQM frames for over 2 seconds. Otherwise online would be 1.
- mss=millis(); //So we've lost communications. Let's turn off the running light.
- faultHandler.raiseFault(CODAUQM, FAULT_MOTORCTRL_COMM, true);
- }
- online=0;//This flag will be set to 1 by received frames.
-}
+ Byte 4 MSB of Torque command value Offset is 32128
+ Byte 5 Security CRC byte.
-/*
-UQM only HAS a single command CAN bus frame - address 0x204 Everything is stuffed into this one frame. It has a 5 byte payload.
-
-Byte 1 - always set to 0
-
-Byte 2 - Command Byte
- Left four bits contain enable disable and forward reverse
- Bits 7/6 DISABLED =01
- Bits 7/6 ENABLE =10
- Bits 5/4 REVERSE=01
- Bits 5/4 FORWARD=10
- Example: Enabled and Forward: 1010
-
- Right four bits (3 to 0) is a sequence counter that counts 0000 to 0111 and back to 0000
-
-Byte 3 LSB of Torque command value.
-
-Byte 4 MSB of Torque command value Offset is 32128
-
-Byte 5 Security CRC byte.
-
-Bytes must be sent IN SEQUENCE and the CRC byte must be appropriate for bytes 2, 3, and 4.
-Values above 32128 are positive torque. Values below 32128 are negative torque
-*/
-
-void CodaMotorController::sendCmd1()
-{
- CodaMotorControllerConfiguration *config = (CodaMotorControllerConfiguration *)getConfiguration();
-
- CAN_FRAME output;
- output.length = 5;
- output.id = 0x204;
- output.extended = 0; //standard frame
- output.rtr = 0;
- output.data.bytes[0] = 0x00; //First byte is always zero.
-
-
- if(operationState==ENABLE)
- {
- output.data.bytes[1] = 0x80; //1000 0000
- }
- else
- {
- output.data.bytes[1] = 0x40; //0100 0000
- }
-
- if(selectedGear==DRIVE)
- {
- output.data.bytes[1] |= 0x20; //xx10 0000
- }
- else
- {
- output.data.bytes[1] |= 0x10;//xx01 0000
- }
-
- sequence+=1; //Increment sequence
- if (sequence==8){sequence=0;} //If we reach 8, go to zero
- output.data.bytes[1] |= sequence; //This should retain left four and add sequence count
- //to right four bits.
- //Requested throttle is [-1000, 1000]
- //Two byte torque request in 0.1NM Can be positive or negative
-
- torqueCommand=32128; //Set our zero offset value -torque=0
- torqueRequested = ((throttleRequested * config->torqueMax) / 1000); //Calculate torque request from throttle position x maximum torque
- if(speedActualspeedMax){torqueCommand += torqueRequested;} //If actual rpm less than max rpm, add torque command to offset
- else {torqueCommand+= torqueRequested/2;} //If at RPM limit, cut torque command in half.
- output.data.bytes[3] = (torqueCommand & 0xFF00) >> 8; //Stow torque command in bytes 2 and 3.
- output.data.bytes[2] = (torqueCommand & 0x00FF);
- output.data.bytes[4] = genCodaCRC(output.data.bytes[1], output.data.bytes[2], output.data.bytes[3]); //Calculate security byte
-
- CanHandler::getInstanceEV()->sendFrame(output); //Mail it.
- timestamp();
-
- Logger::debug("Torque command: %X %X ControlByte: %X LSB %X MSB: %X CRC: %X %d:%d:%d.%d",output.id, output.data.bytes[0],
-output.data.bytes[1],output.data.bytes[2],output.data.bytes[3],output.data.bytes[4], hours, minutes, seconds, milliseconds);
-
-}
+ Bytes must be sent IN SEQUENCE and the CRC byte must be appropriate for bytes 2, 3, and 4.
+ Values above 32128 are positive torque. Values below 32128 are negative torque
+ */
+void CodaMotorController::sendCmd1() {
+ CodaMotorControllerConfiguration *config = (CodaMotorControllerConfiguration *) getConfiguration();
+
+ CAN_FRAME output;
+ canHandlerEv.prepareOutputFrame(&output, 0x204);
+
+ if ((ready || running) && powerOn) {
+ output.data.bytes[1] = 0x80; //1000 0000 enable
+ } else {
+ output.data.bytes[1] = 0x40; //0100 0000 disable
+ }
+
+ if (getGear() == (GEAR_REVERSE ^ config->invertDirection)) {
+ output.data.bytes[1] |= 0x10; //xx01 0000 reverse
+ } else {
+ output.data.bytes[1] |= 0x20; //xx10 0000 forward
+ }
+
+ sequence += 1; //Increment sequence
+ if (sequence == 8) {
+ sequence = 0;
+ } //If we reach 8, go to zero
+ output.data.bytes[1] |= sequence; //This should retain left four and add sequence count to right four bits.
+ //Requested throttle is [-1000, 1000]
+ //Two byte torque request in 0.1NM Can be positive or negative
+
+ uint16_t torqueCommand = 32128; //Set our zero offset value -torque=0
+ if (speedActual < config->speedMax) {
+ torqueCommand += getTorqueRequested();
+ } //If actual rpm less than max rpm, add torque command to offset
+ else {
+ torqueCommand += getTorqueRequested() / 2;
+ } //If at RPM limit, cut torque command in half.
+
+ output.data.bytes[3] = (torqueCommand & 0xFF00) >> 8; //Stow torque command in bytes 2 and 3.
+ output.data.bytes[2] = (torqueCommand & 0x00FF);
+ output.data.bytes[4] = genCodaCRC(output.data.bytes[1], output.data.bytes[2], output.data.bytes[3]); //Calculate security byte
+
+ canHandlerEv.sendFrame(output); //Mail it.
+
+ if (logger.isDebug()) {
+ logger.debug(this, "Torque command: %#x %#x ControlByte: %#x LSB %#x MSB: %#x CRC: %#x", output.id, output.data.bytes[0],
+ output.data.bytes[1], output.data.bytes[2], output.data.bytes[3], output.data.bytes[4]);
+ }
-void CodaMotorController::sendCmd2() {
- CodaMotorControllerConfiguration *config = (CodaMotorControllerConfiguration *)getConfiguration();
-
- /*In the CODA CAN bus capture logs, this command, defined in the UQM manual as a
- 207 watchdog reset, is sent every 480msec. It also always occurs after the last count of
- a sequence ie 57, 67, 97, or A7. But this may just be coincidence.
- By the book, this is to be sent in response to a watchdog timeout.
- We send this in response to receipt of a 20F Watchdog status.
- */
-
- CAN_FRAME output;
- output.length = 8;
- output.id = 0x207;
- output.extended = 0; //standard frame
- output.data.bytes[0] = 0xa5; //This is simply three given values. The 5A appears to be
- output.data.bytes[1] = 0xa5; //the important one.
- output.data.bytes[2] = 0x5a;
- output.data.bytes[3] = 0x00;
- output.data.bytes[4] = 0x00;
- output.data.bytes[5] = 0x00;
- output.data.bytes[6] = 0x00;
- output.data.bytes[7] = 0x00;
-
- CanHandler::getInstanceEV()->sendFrame(output);
- timestamp();
-Logger::debug("Watchdog reset: %X %X %X %d:%d:%d.%d",output.data.bytes[0], output.data.bytes[1],
-output.data.bytes[2], hours, minutes, seconds, milliseconds);
-
- warning=false;
}
-
-DeviceId CodaMotorController::getId() {
- return (CODAUQM);
+void CodaMotorController::sendCmd2() {
+ /*In the CODA CAN bus capture logs, this command, defined in the UQM manual as a
+ 207 watchdog reset, is sent every 480msec. It also always occurs after the last count of
+ a sequence ie 57, 67, 97, or A7. But this may just be coincidence.
+ By the book, this is to be sent in response to a watchdog timeout.
+ We send this in response to receipt of a 20F Watchdog status.
+ */
+
+ CAN_FRAME output;
+ canHandlerEv.prepareOutputFrame(&output, 0x207);
+ output.data.bytes[0] = 0xa5; //This is simply three given values. The 5A appears to be
+ output.data.bytes[1] = 0xa5; //the important one.
+ output.data.bytes[2] = 0x5a;
+
+ canHandlerEv.sendFrame(output);
+ if (logger.isDebug()) {
+ logger.debug(this, "Watchdog reset: %#x %#x %#x", output.data.bytes[0], output.data.bytes[1], output.data.bytes[2]);
+ }
+
+ status.warning = false;
}
-uint32_t CodaMotorController::getTickInterval()
-{
- return CFG_TICK_INTERVAL_MOTOR_CONTROLLER_CODAUQM;
+DeviceId CodaMotorController::getId() {
+ return (CODAUQM);
}
void CodaMotorController::loadConfiguration() {
- CodaMotorControllerConfiguration *config = (CodaMotorControllerConfiguration *)getConfiguration();
+ CodaMotorControllerConfiguration *config = (CodaMotorControllerConfiguration *) getConfiguration();
- if (!config) {
- config = new CodaMotorControllerConfiguration();
- setConfiguration(config);
- }
-
- MotorController::loadConfiguration(); // call parent
+ if (!config) {
+ config = new CodaMotorControllerConfiguration();
+ setConfiguration(config);
+ }
+ MotorController::loadConfiguration(); // call parent
}
void CodaMotorController::saveConfiguration() {
- MotorController::saveConfiguration();
+ MotorController::saveConfiguration();
}
-uint8_t CodaMotorController::genCodaCRC(uint8_t cmd, uint8_t torq_lsb, uint8_t torq_msb)
-{
- int counter;
- uint8_t crc;
- uint16_t temp_torq = torq_lsb + (256 * torq_msb);
- crc = 0x7F; //7F is the answer if bytes 3 and 4 are zero. We build up from there.
-
- //this can be done a little more efficiently but this is clearer to read
- if (((cmd & 0xA0) == 0xA0) || ((cmd & 0x60) == 0x60)) temp_torq += 1;
-
- //Not sure why this happens except to obfuscate the result
- if ((temp_torq % 4) == 3) temp_torq += 4;
-
- //increment over the bits within the torque command
- //and applies a particular XOR for each set bit.
- for (counter = 0; counter < 16; counter++)
- {
- if ((temp_torq & (1 << counter)) == (1 << counter)) crc = (byte)(crc ^ swizzleTable[counter]);
- }
+uint8_t CodaMotorController::genCodaCRC(uint8_t cmd, uint8_t torq_lsb, uint8_t torq_msb) {
+ int counter;
+ uint8_t crc;
+ uint16_t temp_torq = torq_lsb + (256 * torq_msb);
+ crc = 0x7F; //7F is the answer if bytes 3 and 4 are zero. We build up from there.
+
+ //this can be done a little more efficiently but this is clearer to read
+ if (((cmd & 0xA0) == 0xA0) || ((cmd & 0x60) == 0x60))
+ temp_torq += 1;
+
+ //Not sure why this happens except to obfuscate the result
+ if ((temp_torq % 4) == 3)
+ temp_torq += 4;
+
+ //increment over the bits within the torque command
+ //and applies a particular XOR for each set bit.
+ for (counter = 0; counter < 16; counter++) {
+ if ((temp_torq & (1 << counter)) == (1 << counter))
+ crc = (byte) (crc ^ swizzleTable[counter]);
+ }
return (crc);
}
-
-
-
-void CodaMotorController::timestamp()
-{
- milliseconds = (int) (millis()/1) %1000 ;
- seconds = (int) (millis() / 1000) % 60 ;
- minutes = (int) ((millis() / (1000*60)) % 60);
- hours = (int) ((millis() / (1000*60*60)) % 24);
- // char buffer[9];
- //sprintf(buffer,"%02d:%02d:%02d.%03d", hours, minutes, seconds, milliseconds);
- // Serial<
#include "config.h"
#include "MotorController.h"
-#include "sys_io.h"
+#include "SystemIO.h"
#include "TickHandler.h"
#include "CanHandler.h"
+#include "FaultHandler.h"
/*
* Class for Coda UQM Powerphase 100 specific configuration parameters
*/
-class CodaMotorControllerConfiguration : public MotorControllerConfiguration {
+class CodaMotorControllerConfiguration: public MotorControllerConfiguration {
public:
};
-class CodaMotorController: public MotorController, CanObserver {
-
-
+class CodaMotorController: public MotorController {
public:
- virtual void handleTick();
- virtual void handleCanFrame(CAN_FRAME *frame);
- virtual void setup();
-
- CodaMotorController();
- void timestamp();
- DeviceId getId();
- uint32_t getTickInterval();
-
+ virtual void handleTick();
+ virtual void handleCanFrame(CAN_FRAME *frame);
+ virtual void setup();
- virtual void loadConfiguration();
- virtual void saveConfiguration();
+ CodaMotorController();
+ DeviceId getId();
-private:
- byte online; //counter for whether DMOC appears to be operating
- byte alive;
- int activityCount;
- byte sequence;
- uint16_t torqueCommand;
- void sendCmd1();
- void sendCmd2();
- uint8_t genCodaCRC(uint8_t cmd, uint8_t torq_lsb, uint8_t torq_msb);
+ virtual void loadConfiguration();
+ virtual void saveConfiguration();
+private:
+ byte sequence;
+ void sendCmd1();
+ void sendCmd2();
+ uint8_t genCodaCRC(uint8_t cmd, uint8_t torq_lsb, uint8_t torq_msb);
};
#endif /* CODA_H_ */
-
diff --git a/DcDcConverter.cpp b/DcDcConverter.cpp
new file mode 100644
index 0000000..2837ba6
--- /dev/null
+++ b/DcDcConverter.cpp
@@ -0,0 +1,167 @@
+/*
+ * DcDcConverter.cpp
+ *
+ * Parent class for all DC-DC Converters
+ *
+ Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
+
+ 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 "DcDcConverter.h"
+
+DcDcConverter::DcDcConverter() : Device() {
+ hvVoltage = 0;
+ lvVoltage = 0;
+ hvCurrent = 0;
+ lvCurrent = 0;
+ temperature = 0;
+}
+
+DcDcConverter::~DcDcConverter() {
+}
+
+/*
+ * Process event from the tick handler.
+ */
+void DcDcConverter::handleTick()
+{
+ Device::handleTick(); // call parent
+}
+
+/*
+ * Return the device type
+ */
+DeviceType DcDcConverter::getType() {
+ return (DEVICE_DCDC);
+}
+
+int16_t DcDcConverter::getHvCurrent()
+{
+ return hvCurrent;
+}
+
+uint16_t DcDcConverter::getHvVoltage()
+{
+ return hvVoltage;
+}
+
+int16_t DcDcConverter::getLvCurrent()
+{
+ return lvCurrent;
+}
+
+uint16_t DcDcConverter::getLvVoltage()
+{
+ return lvVoltage;
+}
+
+int16_t DcDcConverter::getTemperature()
+{
+ return temperature;
+}
+
+/**
+ * act on messages the super-class does not react upon, like state change
+ * to ready or running which should enable/disable the power-stage of the converter
+ */
+void DcDcConverter::handleStateChange(Status::SystemState oldState, Status::SystemState newState) {
+ Device::handleStateChange(oldState, newState);
+ if (newState == Status::ready || newState == Status::charging || newState == Status::charged
+ || newState == Status::running || newState == Status::batteryHeating) {
+ powerOn = true;
+ } else {
+ powerOn = false;
+ }
+ systemIO.setEnableDcDc(powerOn);
+}
+
+/*
+ * Load configuration data from EEPROM.
+ *
+ * If not available or the checksum is invalid, default values are chosen.
+ */
+void DcDcConverter::loadConfiguration()
+{
+ DcDcConverterConfiguration *config = (DcDcConverterConfiguration *) getConfiguration();
+
+ if (!config) { // as lowest sub-class make sure we have a config object
+ config = new DcDcConverterConfiguration();
+ setConfiguration(config);
+ }
+
+ Device::loadConfiguration(); // call parent
+ logger.info(this, "DC-DC converter configuration:");
+
+#ifdef USE_HARD_CODED
+
+ if (false) {
+#else
+ if (prefsHandler->checksumValid()) { //checksum is good, read in the values stored in EEPROM
+#endif
+ prefsHandler->read(EEDC_BOOST_MODE, &config->mode);
+ prefsHandler->read(EEDC_LOW_VOLTAGE, &config->lowVoltageCommand);
+ prefsHandler->read(EEDC_HV_UNDERVOLTAGE_LIMIT, &config->hvUndervoltageLimit);
+ prefsHandler->read(EEDC_LV_BUCK_CURRENT_LIMIT, &config->lvBuckModeCurrentLimit);
+ prefsHandler->read(EEDC_HV_BUCK_CURRENT_LIMIT, &config->hvBuckModeCurrentLimit);
+ prefsHandler->read(EEDC_HIGH_VOLTAGE, &config->highVoltageCommand);
+ prefsHandler->read(EEDC_LV_UNDERVOLTAGE_LIMIT, &config->lvUndervoltageLimit);
+ prefsHandler->read(EEDC_LV_BOOST_CURRENT_LIMIT, &config->lvBoostModeCurrentLinit);
+ prefsHandler->read(EEDC_HV_BOOST_CURRENT_LIMIT, &config->hvBoostModeCurrentLimit);
+ } else { //checksum invalid. Reinitialize values and store to EEPROM
+ config->mode = false; // default mode: buck, meaning: reduce from HV to LV
+ config->lowVoltageCommand = 135; // 13.5 V
+ config->hvUndervoltageLimit = 330; // 330 V
+ config->lvBuckModeCurrentLimit = 250; // 250 A
+ config->hvBuckModeCurrentLimit = 200; // 20.0 A
+ config->highVoltageCommand = 0;
+ config->lvUndervoltageLimit = 0;
+ config->lvBoostModeCurrentLinit = 0;
+ config->hvBoostModeCurrentLimit = 0;
+ saveConfiguration();
+ }
+
+ logger.info(this, "operation mode: %s", (config->mode ? "boost" : "buck"));
+ logger.info(this, "buck : LV command %.1fV (max %dA), HV min %dV (max %.1fA)", (float) config->lowVoltageCommand / 10.0F, config->lvBuckModeCurrentLimit, config->hvUndervoltageLimit, (float) config->hvBuckModeCurrentLimit / 10.0F);
+ logger.info(this, "boost: HV command %dV (max %.1fA), LV min %.1fV (max %dA)", config->highVoltageCommand, (float) config->hvBoostModeCurrentLimit / 10.0, (float) config->lvUndervoltageLimit / 10.0F, config->lvBoostModeCurrentLinit);
+}
+
+/*
+ * Store the current configuration parameters to EEPROM.
+ */
+void DcDcConverter::saveConfiguration()
+{
+ DcDcConverterConfiguration *config = (DcDcConverterConfiguration *) getConfiguration();
+
+ Device::saveConfiguration(); // call parent
+
+ prefsHandler->write(EEDC_BOOST_MODE, config->mode);
+ prefsHandler->write(EEDC_LOW_VOLTAGE, config->lowVoltageCommand);
+ prefsHandler->write(EEDC_HV_UNDERVOLTAGE_LIMIT, config->hvUndervoltageLimit);
+ prefsHandler->write(EEDC_LV_BUCK_CURRENT_LIMIT, config->lvBuckModeCurrentLimit);
+ prefsHandler->write(EEDC_HV_BUCK_CURRENT_LIMIT, config->hvBuckModeCurrentLimit);
+ prefsHandler->write(EEDC_HIGH_VOLTAGE, config->highVoltageCommand);
+ prefsHandler->write(EEDC_LV_UNDERVOLTAGE_LIMIT, config->lvUndervoltageLimit);
+ prefsHandler->write(EEDC_LV_BOOST_CURRENT_LIMIT, config->lvBoostModeCurrentLinit);
+ prefsHandler->write(EEDC_HV_BOOST_CURRENT_LIMIT, config->hvBoostModeCurrentLimit);
+
+ prefsHandler->saveChecksum();
+}
diff --git a/DcDcConverter.h b/DcDcConverter.h
new file mode 100644
index 0000000..a2c1e13
--- /dev/null
+++ b/DcDcConverter.h
@@ -0,0 +1,78 @@
+/*
+ * DcDcConverter.h
+ *
+ * Parent class for DC-DC Converters
+ *
+Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
+
+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 DCDCCONVERTER_H_
+#define DCDCCONVERTER_H_
+
+#include
+#include "config.h"
+#include "Device.h"
+#include "CanHandler.h"
+
+class DcDcConverterConfiguration : public DeviceConfiguration
+{
+public:
+ uint8_t mode; // the operation mode to use (0=buck, 1=boost)
+ uint16_t lowVoltageCommand; // in 0.1V, commanded LV voltage in buck mode
+ uint16_t hvUndervoltageLimit; // in 1V, HV under-voltage limit in buck mode
+ uint16_t lvBuckModeCurrentLimit; // in 1A
+ uint16_t hvBuckModeCurrentLimit; // in 0.1A
+ uint16_t highVoltageCommand; // 1V, commanded HV in boost mode
+ uint16_t lvUndervoltageLimit; // in 0.1V, LV under-voltage limit in boost mode
+ uint16_t lvBoostModeCurrentLinit; // in 1A
+ uint16_t hvBoostModeCurrentLimit; // in 0.1A
+};
+
+class DcDcConverter : public Device
+{
+public:
+ DcDcConverter();
+ ~DcDcConverter();
+ void handleTick();
+ void handleStateChange(Status::SystemState, Status::SystemState);
+ DeviceType getType();
+ int16_t getHvCurrent();
+ uint16_t getHvVoltage();
+ int16_t getLvCurrent();
+ uint16_t getLvVoltage();
+ int16_t getTemperature();
+
+ void loadConfiguration();
+ void saveConfiguration();
+
+protected:
+ uint16_t hvVoltage; // in 0.1V
+ uint16_t lvVoltage; // in 0.1V
+ int16_t hvCurrent; // in 0.1A
+ int16_t lvCurrent; // in 1A
+ int16_t temperature; // in 0.1C
+
+private:
+};
+
+#endif
diff --git a/Device.cpp b/Device.cpp
index 85c0130..1512ec6 100644
--- a/Device.cpp
+++ b/Device.cpp
@@ -27,62 +27,220 @@
#include "Device.h"
#include "DeviceManager.h"
-Device::Device() {
- deviceConfiguration = NULL;
- prefsHandler = NULL;
- //since all derived classes eventually call this base method this will cause every device to auto register itself with the device manager
- DeviceManager::getInstance()->addDevice(this);
- commonName = "Generic Device";
+/**
+ * Constructor - initialize class variables
+ */
+Device::Device()
+{
+ prefsHandler = NULL;
+
+ commonName = "Generic Device";
+ deviceConfiguration = NULL;
+
+ ready = false;
+ running = false;
+ powerOn = false;
+}
+
+/**
+ * Destructor
+ */
+Device::~Device()
+{
+}
+
+/**
+ * Called during initialization of the device.
+ * May be called multiple times e.g. when recovering from an error
+ * or disabling and re-enabling the device.
+ */
+void Device::setup()
+{
+ tickHandler.detach(this);
+
+ ready = false;
+ running = false;
+ powerOn = false;
+
+ loadConfiguration();
+
+ logger.info(this, "device started");
+}
+
+/**
+ * Called during tear-down of the device.
+ * May be called multiple times e.g. when disabling the device.
+ */
+void Device::tearDown()
+{
+ tickHandler.detach(this);
+ ready = false;
+ running = false;
+ powerOn = false;
+
+ logger.info(this, "device stopped");
+}
+
+/**
+ * Retrieve the common name of the device.
+ */
+String Device::getCommonName()
+{
+ return commonName;
+}
+
+/**
+ * Handle a timer event - called by the TickHandler
+ */
+void Device::handleTick()
+{
+}
+
+/**
+ * Enable the device in the preferences and activate it
+ */
+void Device::enable()
+{
+ if (isEnabled()) {
+ return;
+ }
+ if (prefsHandler != NULL && prefsHandler->setEnabled(true)) {
+ prefsHandler->suggestCacheWrite(); //just in case someone power cycles quickly
+ logger.info(this, "Successfully enabled device %s.(%#x)", commonName.c_str(), getId());
+ }
+ setup();
}
-//Empty functions to handle these callbacks if the derived classes don't
+/**
+ * Deactivate the device and disable it in the preferences
+ */
+void Device::disable()
+{
+ if (!isEnabled()) {
+ return;
+ }
+ if (prefsHandler != NULL && prefsHandler->setEnabled(false)) {
+ prefsHandler->suggestCacheWrite(); //just in case someone power cycles quickly
+ logger.info(this, "Successfully disabled device %s.(%#x)", commonName.c_str(), getId());
+ }
+ tearDown();
+}
-void Device::setup() {
+/**
+ * Returns if the device is enabled via preferences
+ */
+bool Device::isEnabled()
+{
+ if (prefsHandler == NULL) {
+ return true;
+ }
+ return prefsHandler->isEnabled();
}
-char* Device::getCommonName() {
- return commonName;
+/**
+ * Is the device itself ready for operation ?
+ */
+bool Device::isReady()
+{
+ return ready;
}
-void Device::handleTick() {
+/**
+ * Is the device reporting that it's running ?
+ */
+bool Device::isRunning()
+{
+ return running;
}
-uint32_t Device::getTickInterval() {
- return 0;
+/**
+ * Handle incoming messages from the DeviceManager. A message might
+ * indicate a change in the system state, a command to reload the configuration
+ * or other actions.
+ */
+void Device::handleMessage(uint32_t msgType, void* message)
+{
+ switch (msgType) {
+ case MSG_SOFT_FAULT:
+ //TODO: implement action/method for soft fault
+ break;
+ case MSG_HARD_FAULT:
+ //TODO: implement action/method for hard fault
+ break;
+ case MSG_DISABLE:
+ disable();
+ break;
+ case MSG_ENABLE:
+ enable();
+ break;
+ case MSG_KILL:
+ tearDown();
+ break;
+ case MSG_STATE_CHANGE:
+ Status::SystemState *state = (Status::SystemState *) message;
+ handleStateChange(state[0], state[1]);
+ break;
+ }
}
-//just bubbles up the value from the preference handler.
-bool Device::isEnabled() {
- return prefsHandler->isEnabled();
+/**
+ * React on state changes.
+ * Subclasses may overwrite the method but should call the parent.
+ */
+void Device::handleStateChange(Status::SystemState oldState, Status::SystemState newState)
+{
+ switch (newState) {
+ case Status::init:
+ this->setup();
+ break;
+ case Status::error: // stop all devices in case of an error
+ this->tearDown();
+ break;
+ case Status::shutdown: // stop all devices
+ this->tearDown();
+ break;
+ default:
+ break;
+ }
}
-void Device::handleMessage(uint32_t msgType, void* message) {
- switch (msgType) {
- case MSG_STARTUP:
- this->setup();
- break;
- }
+/**
+ * If a flag is set in a bitfield, add a message part to a message
+ */
+void Device::appendMessage(String &message, uint32_t bitfield, uint32_t flag, String part) {
+ if (bitfield & flag) {
+ if (message.length() > 0) {
+ message.concat(", ");
+ }
+ message.concat(part);
+ }
}
-DeviceType Device::getType() {
- return DEVICE_NONE;
+DeviceType Device::getType()
+{
+ return DEVICE_NONE;
}
-DeviceId Device::getId() {
- return INVALID;
+DeviceId Device::getId()
+{
+ return INVALID;
}
-void Device::loadConfiguration() {
+void Device::loadConfiguration()
+{
}
-void Device::saveConfiguration() {
+void Device::saveConfiguration()
+{
}
-DeviceConfiguration *Device::getConfiguration() {
- return this->deviceConfiguration;
+DeviceConfiguration *Device::getConfiguration()
+{
+ return this->deviceConfiguration;
}
-void Device::setConfiguration(DeviceConfiguration *configuration) {
- this->deviceConfiguration = configuration;
+void Device::setConfiguration(DeviceConfiguration *configuration)
+{
+ this->deviceConfiguration = configuration;
}
diff --git a/Device.h b/Device.h
index 3a16922..c6d07f6 100644
--- a/Device.h
+++ b/Device.h
@@ -29,47 +29,67 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
#include
#include "config.h"
+#include "Status.h"
#include "DeviceTypes.h"
#include "eeprom_layout.h"
#include "PrefHandler.h"
#include "Sys_Messages.h"
-#include "FaultHandler.h"
+#include "SystemIO.h"
-/*
+class DeviceManager;
+
+/**
* A abstract class to hold device configuration. It is to be accessed
* by sub-classes via getConfiguration() and then cast into its
* correct sub-class.
*/
-class DeviceConfiguration {
+class DeviceConfiguration
+{
};
-/*
- * A abstract class for all Devices.
+/**
+ * Base class for all Devices.
*/
-class Device: public TickObserver {
+class Device: public TickObserver
+{
public:
- Device();
- virtual void setup();
- virtual void handleMessage(uint32_t, void* );
- virtual DeviceType getType();
- virtual DeviceId getId();
- void handleTick();
- bool isEnabled();
- virtual uint32_t getTickInterval();
- char* getCommonName();
-
- virtual void loadConfiguration();
- virtual void saveConfiguration();
- DeviceConfiguration *getConfiguration();
- void setConfiguration(DeviceConfiguration *);
+ Device();
+ virtual ~Device();
+ virtual void setup();
+ virtual void tearDown();
+
+ virtual void handleTick();
+ virtual void handleMessage(uint32_t, void*);
+ virtual void handleStateChange(Status::SystemState, Status::SystemState);
+
+ virtual DeviceType getType();
+ virtual DeviceId getId();
+ String getCommonName();
+
+ void enable();
+ void disable();
+
+ bool isEnabled();
+ bool isReady();
+ bool isRunning();
+
+ virtual void loadConfiguration();
+ virtual void saveConfiguration();
+ DeviceConfiguration *getConfiguration();
+ void setConfiguration(DeviceConfiguration *);
protected:
- PrefHandler *prefsHandler;
- char *commonName;
+ PrefHandler *prefsHandler; /*!> pointer to device specific instance of PrefHandler */
+ String commonName; /*!> the device's common name */
+ bool ready; /*!> set if the device itself reports that it's ready for operation */
+ bool running; /*!> set if the device itself reports that it's running / active */
+ bool powerOn; /*!> set if the device has to be powered on - e.g. the power stage of a motor controller or DC-DC converter, may be ignored by various devices */
+
+ void appendMessage(String &error, uint32_t bitfield, uint32_t flag, String message);
private:
- DeviceConfiguration *deviceConfiguration; // reference to the currently active configuration
+ DeviceConfiguration *deviceConfiguration; /*!> reference to the currently active configuration */
};
#endif /* DEVICE_H_ */
diff --git a/DeviceManager.cpp b/DeviceManager.cpp
index ff486a2..d3050f4 100644
--- a/DeviceManager.cpp
+++ b/DeviceManager.cpp
@@ -37,74 +37,66 @@
#include "DeviceManager.h"
-DeviceManager *DeviceManager::deviceManager = NULL;
-
-DeviceManager::DeviceManager() {
- throttle = NULL;
- brake = NULL;
- motorController = NULL;
- for (int i = 0; i < CFG_DEV_MGR_MAX_DEVICES; i++)
- devices[i] = NULL;
-}
+DeviceManager deviceManager;
-/*
- * Get the instance of the DeviceManager (singleton pattern)
- *
- * Note: It's a simple singleton implementation - no worries about
- * thread-safety and memory-leaks, this object lives as long as the
- * Arduino has power.
- */
-DeviceManager *DeviceManager::getInstance() {
- if (deviceManager == NULL)
- deviceManager = new DeviceManager();
- return deviceManager;
+DeviceManager::DeviceManager()
+{
+ throttle = NULL;
+ brake = NULL;
+ motorController = NULL;
+ charger = NULL;
+ dcDcConverter = NULL;
+ batteryManager = NULL;
+
+ for (int i = 0; i < CFG_DEV_MGR_MAX_DEVICES; i++) {
+ devices[i] = NULL;
+ }
}
/*
* Add the specified device to the list of registered devices
*/
-void DeviceManager::addDevice(Device *device) {
- if (findDevice(device) == -1) {
- int8_t i = findDevice(NULL);
- if (i != -1) {
- devices[i] = device;
- } else {
- Logger::error("unable to register device, max number of devices reached.");
- }
- }
- /*
- switch (device->getType()) {
- case DEVICE_THROTTLE:
- throttle = (Throttle *) device;
- break;
- case DEVICE_BRAKE:
- brake = (Throttle *) device;
- break;
- case DEVICE_MOTORCTRL:
- motorController = (MotorController *) device;
- break;
- }
- */
+void DeviceManager::addDevice(Device *device)
+{
+ logger.debug(device, "add device: %s (id: %#x)", device->getCommonName().c_str(), device->getId());
+
+ if (findDevice(device) == -1) {
+ int8_t i = findDevice(NULL);
+
+ if (i != -1) {
+ devices[i] = device;
+ } else {
+ logger.error(device, "unable to register device, max number of devices reached.");
+ }
+ }
}
/*
* Remove the specified device from the list of registered devices
*/
-void DeviceManager::removeDevice(Device *device) {
- int8_t i = findDevice(NULL);
- if (i != -1)
- devices[i] = NULL;
- switch (device->getType()) {
- case DEVICE_THROTTLE:
- throttle = NULL;
- break;
- case DEVICE_BRAKE:
- brake = NULL;
- break;
- case DEVICE_MOTORCTRL:
- motorController = NULL;
- break;
- }
+void DeviceManager::removeDevice(Device *device)
+{
+ int8_t i = findDevice(NULL);
+
+ if (i != -1) {
+ devices[i] = NULL;
+ }
+
+ switch (device->getType()) {
+ case DEVICE_THROTTLE:
+ throttle = NULL;
+ break;
+
+ case DEVICE_BRAKE:
+ brake = NULL;
+ break;
+
+ case DEVICE_MOTORCTRL:
+ motorController = NULL;
+ break;
+ default:
+ break;
+ }
}
/*Add a new tick handler to the specified device. It should
@@ -132,200 +124,151 @@ void DeviceManager::removeDevice(Device *device) {
whatever you want. The standard message types are to enforce standard messages for easy
intercommunication.
*/
-void DeviceManager::sendMessage(DeviceType devType, DeviceId devId, uint32_t msgType, void* message)
+bool DeviceManager::sendMessage(DeviceType devType, DeviceId devId, uint32_t msgType, void* message)
{
- for (int i = 0; i < CFG_DEV_MGR_MAX_DEVICES; i++)
- {
- if (devices[i] && devices[i]->isEnabled()) //does this object exist and is it enabled?
- {
- if (devType == DEVICE_ANY || devType == devices[i]->getType())
- {
- if (devId == INVALID || devId == devices[i]->getId())
- {
- Logger::debug("Sending msg to device with ID %X", devices[i]->getId());
- devices[i]->handleMessage(msgType, message);
- }
- }
- }
- }
+ bool foundDevice = false;
+ for (int i = 0; i < CFG_DEV_MGR_MAX_DEVICES; i++) {
+ if (devices[i] && (devices[i]->isEnabled() || msgType == MSG_ENABLE)) { //does this object exist and is it enabled?
+ if (devType == DEVICE_ANY || devType == devices[i]->getType()) {
+ if (devId == INVALID || devId == devices[i]->getId()) {
+ if (logger.isDebug()) {
+ logger.debug("Sending msg %#x to device %#x", msgType, devices[i]->getId());
+ }
+ devices[i]->handleMessage(msgType, message);
+ foundDevice = true;
+ }
+ }
+ }
+ }
+ return foundDevice;
}
-void DeviceManager::setParameter(DeviceType deviceType, DeviceId deviceId, uint32_t msgType, char *key, char *value) {
- char *params[] = { key, value };
- sendMessage(deviceType, deviceId, msgType, params);
-}
-
-void DeviceManager::setParameter(DeviceType deviceType, DeviceId deviceId, uint32_t msgType, char *key, uint32_t value) {
- char buffer[15];
- sprintf(buffer, "%lu", value);
- setParameter(deviceType, deviceId, msgType, key, buffer);
-}
-
-uint8_t DeviceManager::getNumThrottles() {
- return countDeviceType(DEVICE_THROTTLE);
+void DeviceManager::setParameter(DeviceType deviceType, DeviceId deviceId, uint32_t msgType, char *key, char *value)
+{
+ char *params[] = { key, value };
+ sendMessage(deviceType, deviceId, msgType, params);
}
-uint8_t DeviceManager::getNumControllers() {
- return countDeviceType(DEVICE_MOTORCTRL);
+void DeviceManager::setParameter(DeviceType deviceType, DeviceId deviceId, uint32_t msgType, char *key, uint32_t value)
+{
+ char buffer[15];
+ sprintf(buffer, "%lu", value);
+ setParameter(deviceType, deviceId, msgType, key, buffer);
}
-uint8_t DeviceManager::getNumBMS() {
- return countDeviceType(DEVICE_BMS);
+Throttle *DeviceManager::getAccelerator()
+{
+ if (!throttle) {
+ throttle = (Throttle *) getDeviceByType(DEVICE_THROTTLE);
+ }
+ return throttle;
}
-uint8_t DeviceManager::getNumChargers() {
- return countDeviceType(DEVICE_CHARGER);
+Throttle *DeviceManager::getBrake()
+{
+ if (!brake) {
+ brake = (Throttle *) getDeviceByType(DEVICE_BRAKE);
+ }
+ return brake;
}
-uint8_t DeviceManager::getNumDisplays() {
- return countDeviceType(DEVICE_DISPLAY);
+MotorController *DeviceManager::getMotorController()
+{
+ if (!motorController) {
+ motorController = (MotorController *) getDeviceByType(DEVICE_MOTORCTRL);
+ }
+ return motorController;
}
-Throttle *DeviceManager::getAccelerator() {
- //try to find one if nothing registered. Cache it if we find one
- if (!throttle) throttle = (Throttle *)getDeviceByType(DEVICE_THROTTLE);
-
- //if there is no throttle then instantiate a dummy throttle
- //so down range code doesn't puke
- if (!throttle)
- {
- Logger::debug("getAccelerator() called but there is no registered accelerator!");
- return 0; //NULL!
- }
- return throttle;
+Charger *DeviceManager::getCharger()
+{
+ if (!charger) {
+ charger = (Charger *) getDeviceByType(DEVICE_CHARGER);
+ }
+ return charger;
}
-Throttle *DeviceManager::getBrake() {
-
- if (!brake) brake = (Throttle *)getDeviceByType(DEVICE_BRAKE);
-
- if (!brake)
- {
- //Logger::debug("getBrake() called but there is no registered brake!");
- return 0; //NULL!
- }
- return brake;
+DcDcConverter *DeviceManager::getDcDcConverter()
+{
+ if (!dcDcConverter) {
+ dcDcConverter = (DcDcConverter *) getDeviceByType(DEVICE_DCDC);
+ }
+ return dcDcConverter;
}
-MotorController *DeviceManager::getMotorController() {
- if (!motorController) motorController = (MotorController *)getDeviceByType(DEVICE_MOTORCTRL);
-
- if (!motorController)
- {
- Logger::debug("getMotorController() called but there is no registered motor controller!");
- return 0; //NULL!
- }
- return motorController;
+BatteryManager *DeviceManager::getBatteryManager()
+{
+ if (!batteryManager) {
+ batteryManager = (BatteryManager *) getDeviceByType(DEVICE_BMS);
+ }
+ return batteryManager;
}
/*
Allows one to request a reference to a device with the given ID. This lets code specifically request a certain
device. Normally this would be a bad idea because it sort of breaks the OOP design philosophy of polymorphism
-but sometimes you can't help it.
+but sometimes you can't help it.
*/
Device *DeviceManager::getDeviceByID(DeviceId id)
{
- for (int i = 0; i < CFG_DEV_MGR_MAX_DEVICES; i++)
- {
- if (devices[i])
- {
- if (devices[i]->getId() == id) return devices[i];
- }
- }
- Logger::debug("getDeviceByID - No device with ID: %X", (int)id);
- return 0; //NULL!
+ for (int i = 0; i < CFG_DEV_MGR_MAX_DEVICES; i++) {
+ if (devices[i]) {
+ if (devices[i]->getId() == id) {
+ return devices[i];
+ }
+ }
+ }
+
+ logger.debug("getDeviceByID - No device with ID: %#x", (int) id);
+ return NULL;
}
/*
The more object oriented version of the above function. Allows one to find the first device that matches
-a given type.
+a given type and that is enabled.
*/
Device *DeviceManager::getDeviceByType(DeviceType type)
{
- for (int i = 0; i < CFG_DEV_MGR_MAX_DEVICES; i++)
- {
- if (devices[i] && devices[i]->isEnabled())
- {
- if (devices[i]->getType() == type) return devices[i];
- }
- }
- Logger::debug("getDeviceByType - No devices of type: %X", (int)type);
- return 0; //NULL!
+ for (int i = 0; i < CFG_DEV_MGR_MAX_DEVICES; i++) {
+ if (devices[i]) {
+ if (devices[i]->getType() == type && devices[i]->isEnabled()) {
+ return devices[i];
+ }
+ }
+ }
+ return NULL;
}
/*
* Find the position of a device in the devices array
* /retval the position of the device or -1 if not found.
*/
-int8_t DeviceManager::findDevice(Device *device) {
- for (int i = 0; i < CFG_DEV_MGR_MAX_DEVICES; i++) {
- if (device == devices[i])
- return i;
- }
- return -1;
-}
-
-/*
- * Count the number of registered devices of a certain type.
- */
-uint8_t DeviceManager::countDeviceType(DeviceType deviceType) {
- uint8_t count = 0;
- for (int i = 0; i < CFG_DEV_MGR_MAX_DEVICES; i++) {
- if (devices[i]->getType() == deviceType)
- count++;
- }
- return count;
-}
+int8_t DeviceManager::findDevice(Device *device)
+{
+ for (int i = 0; i < CFG_DEV_MGR_MAX_DEVICES; i++) {
+ if (device == devices[i]) {
+ return i;
+ }
+ }
-void DeviceManager::printDeviceList() {
- Logger::console("Currently enabled devices: (DISABLE= to disable)");
- for (int i = 0; i < CFG_DEV_MGR_MAX_DEVICES; i++) {
- if (devices[i] && devices[i]->isEnabled()) {
- Logger::console(" %X %s", devices[i]->getId(), devices[i]->getCommonName());
- }
- }
-
- Logger::console("Currently disabled devices: (ENABLE= to enable)");
- for (int i = 0; i < CFG_DEV_MGR_MAX_DEVICES; i++) {
- if (devices[i] && !devices[i]->isEnabled()) {
- Logger::console(" %X %s", devices[i]->getId(), devices[i]->getCommonName());
- }
- }
+ return -1;
}
+void DeviceManager::printDeviceList()
+{
+ logger.console("Currently enabled devices: (DISABLE= to disable)");
-void DeviceManager::updateWifi() {
-
- sendMessage(DEVICE_WIFI, ICHIP2128, MSG_CONFIG_CHANGE, NULL); //Load all our other parameters first
-
- char param [2][20]; //A two element array containing id and enable state
- char *paramPtr[2] = { ¶m[0][0], ¶m[1][0] }; //A two element array of pointers, pointing to the addresses of row 1 and row 2 of array.
- //paramPtr[0] then contains address of param row 0 element 0
- //paramPtr[1] then contains address of param row 1 element 0.
-
-
- for (int i = 0; i < CFG_DEV_MGR_MAX_DEVICES; i++) { //Find all devices that are enabled and load into array
- if (devices[i] && devices[i]->isEnabled())
- {
- sprintf(paramPtr[0],"x%X",devices[i]->getId());
- sprintf(paramPtr[1],"255");
- // Logger::console(" Device: %s value %s", paramPtr[0], paramPtr[1]);
-
- sendMessage(DEVICE_WIFI, ICHIP2128, MSG_SET_PARAM, paramPtr); //Send the array to ichip by id (ie 1031) 255 indicates enabled
- }
- }
-
- for (int i = 0; i < CFG_DEV_MGR_MAX_DEVICES; i++) { //Find all devices that are NOT enabled and load into array
- if (devices[i] && !devices[i]->isEnabled())
- {
- sprintf(paramPtr[0],"x%X",devices[i]->getId());
- sprintf(paramPtr[1],"0");
- // Logger::console(" Device: %s value %s", paramPtr[0], paramPtr[1]);
- sendMessage(DEVICE_WIFI, ICHIP2128, MSG_SET_PARAM, paramPtr); //Send array to ichip by id (ie 1002) 0 indicates disabled
- }
- }
-
-
-}
+ for (int i = 0; i < CFG_DEV_MGR_MAX_DEVICES; i++) {
+ if (devices[i] && devices[i]->isEnabled()) {
+ logger.console(" %#x %s", devices[i]->getId(), devices[i]->getCommonName().c_str());
+ }
+ }
+ logger.console("Currently disabled devices: (ENABLE= to enable)");
+ for (int i = 0; i < CFG_DEV_MGR_MAX_DEVICES; i++) {
+ if (devices[i] && !devices[i]->isEnabled()) {
+ logger.console(" %#x %s", devices[i]->getId(), devices[i]->getCommonName().c_str());
+ }
+ }
+}
diff --git a/DeviceManager.h b/DeviceManager.h
index 24a9e53..e4e4660 100644
--- a/DeviceManager.h
+++ b/DeviceManager.h
@@ -29,50 +29,49 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
#include "config.h"
#include "Throttle.h"
#include "MotorController.h"
-#include "CanHandler.h"
-#include "Device.h"
+#include "Charger.h"
+#include "DcDcConverter.h"
+#include "BatteryManager.h"
#include "Sys_Messages.h"
#include "DeviceTypes.h"
+class Device;
+class Charger;
class MotorController; // cyclic reference between MotorController and DeviceManager
-class DeviceManager {
+class DeviceManager
+{
public:
- static DeviceManager *getInstance();
- void addDevice(Device *device);
- void removeDevice(Device *device);
-// void addTickObserver(TickObserver *observer, uint32_t frequency);
-// void addCanObserver(CanObserver *observer, uint32_t id, uint32_t mask, bool extended, CanHandler::CanBusNode canBus);
- void sendMessage(DeviceType deviceType, DeviceId deviceId, uint32_t msgType, void* message);
- void setParameter(DeviceType deviceType, DeviceId deviceId, uint32_t msgType, char *key, char *value);
- void setParameter(DeviceType deviceType, DeviceId deviceId, uint32_t msgType, char *key, uint32_t value);
- uint8_t getNumThrottles();
- uint8_t getNumControllers();
- uint8_t getNumBMS();
- uint8_t getNumChargers();
- uint8_t getNumDisplays();
- Throttle *getAccelerator();
- Throttle *getBrake();
- MotorController *getMotorController();
- Device *getDeviceByID(DeviceId);
- Device *getDeviceByType(DeviceType);
- void printDeviceList();
- void updateWifi();
- Device *updateWifiByID(DeviceId);
+ DeviceManager();
+ void addDevice(Device *device);
+ void removeDevice(Device *device);
+ bool sendMessage(DeviceType deviceType, DeviceId deviceId, uint32_t msgType, void* message);
+ void setParameter(DeviceType deviceType, DeviceId deviceId, uint32_t msgType, char *key, char *value);
+ void setParameter(DeviceType deviceType, DeviceId deviceId, uint32_t msgType, char *key, uint32_t value);
+ Throttle *getAccelerator();
+ Throttle *getBrake();
+ MotorController *getMotorController();
+ Charger *getCharger();
+ DcDcConverter *getDcDcConverter();
+ BatteryManager *getBatteryManager();
+ Device *getDeviceByID(DeviceId);
+ Device *getDeviceByType(DeviceType);
+ void printDeviceList();
protected:
private:
- DeviceManager(); // private constructor
- static DeviceManager *deviceManager;
+ Device *devices[CFG_DEV_MGR_MAX_DEVICES];
+ Throttle *throttle;
+ Throttle *brake;
+ MotorController *motorController;
+ DcDcConverter *dcDcConverter;
+ Charger *charger;
+ BatteryManager *batteryManager;
- Device *devices[CFG_DEV_MGR_MAX_DEVICES];
- Throttle *throttle;
- Throttle *brake;
- MotorController *motorController;
-
- int8_t findDevice(Device *device);
- uint8_t countDeviceType(DeviceType deviceType);
+ int8_t findDevice(Device *device);
};
+extern DeviceManager deviceManager;
+
#endif
diff --git a/DeviceTypes.h b/DeviceTypes.h
index a4cc9e7..20c4d8e 100644
--- a/DeviceTypes.h
+++ b/DeviceTypes.h
@@ -28,38 +28,73 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
#define DEVICE_TYPES_H_
enum DeviceType {
- DEVICE_ANY,
- DEVICE_MOTORCTRL,
- DEVICE_BMS,
- DEVICE_CHARGER,
- DEVICE_DISPLAY,
- DEVICE_THROTTLE,
- DEVICE_BRAKE,
- DEVICE_MISC,
- DEVICE_WIFI,
- DEVICE_NONE
+ DEVICE_ANY,
+ DEVICE_MOTORCTRL,
+ DEVICE_BMS,
+ DEVICE_CHARGER,
+ DEVICE_DISPLAY,
+ DEVICE_THROTTLE,
+ DEVICE_BRAKE,
+ DEVICE_MISC,
+ DEVICE_WIFI,
+ DEVICE_DCDC,
+ DEVICE_IO,
+ DEVICE_NONE
};
-enum DeviceId { //unique device ID for every piece of hardware possible
- DMOC645 = 0x1000,
- BRUSA_DMC5 = 0x1001,
+// unique device ID for every piece of hardware possible
+// maximum ID number: 0x7fff (refer to PrefHandler, first bit of 16bit is used as enable flag)
+enum DeviceId {
+ NEW = 0x0000,
+ DMOC645 = 0x1000,
+ BRUSA_DMC5 = 0x1001,
CODAUQM = 0x1002,
- BRUSACHARGE = 0x1010,
- TCCHCHARGE = 0x1020,
- THROTTLE = 0x1030,
- POTACCELPEDAL = 0x1031,
- POTBRAKEPEDAL = 0x1032,
- CANACCELPEDAL = 0x1033,
- CANBRAKEPEDAL = 0x1034,
- ICHIP2128 = 0x1040,
- THINKBMS = 0x2000,
- FAULTSYS = 0x4000,
- SYSTEM = 0x5000,
- HEARTBEAT = 0x5001,
- MEMCACHE = 0x5002,
- PIDLISTENER = 0x6000,
- ELM327EMU = 0x6500,
- INVALID = 0xFFFF
+ BRUSA_NLG5 = 0x1010,
+ TCCHCHARGE = 0x1020,
+ LEARCHARGE = 0x1022,
+ POTACCELPEDAL = 0x1031,
+ POTBRAKEPEDAL = 0x1032,
+ CANACCELPEDAL = 0x1033,
+ CANBRAKEPEDAL = 0x1034,
+ ICHIP2128 = 0x1040,
+ ESP32WIFI = 0x1041,
+ THINKBMS = 0x2000,
+ ORIONBMS = 0x2001,
+ BRUSA_BSC6 = 0x3000,
+ FAULTSYS = 0x4000,
+ SYSTEM = 0x5000,
+ HEARTBEAT = 0x5001,
+ MEMCACHE = 0x5002,
+ CANIO = 0x5003,
+ STATUSINDICATOR = 0x5010,
+ CANOBD2= 0x6000,
+ ELM327EMU = 0x6500,
+ INVALID = 0xFFFF
};
+// this array must list all and only devices which can be enabled/disabled
+const DeviceId deviceIds[] = {
+ DMOC645,
+ BRUSA_DMC5,
+ CODAUQM,
+ BRUSA_NLG5,
+ TCCHCHARGE,
+ LEARCHARGE,
+ POTACCELPEDAL,
+ POTBRAKEPEDAL,
+ CANACCELPEDAL,
+ CANBRAKEPEDAL,
+ ICHIP2128,
+ ESP32WIFI,
+ THINKBMS,
+ ORIONBMS,
+ BRUSA_BSC6,
+ HEARTBEAT,
+ CANIO,
+ CANOBD2,
+ ELM327EMU
+};
+
+const uint8_t deviceIdsSize = (sizeof(deviceIds) / sizeof(DeviceId));
+
#endif /* DEVICE_TYPES_H_ */
diff --git a/DmocMotorController.cpp b/DmocMotorController.cpp
index b29dead..efe97b9 100644
--- a/DmocMotorController.cpp
+++ b/DmocMotorController.cpp
@@ -3,26 +3,26 @@
*
* Interface to the DMOC - Handles sending of commands and reception of status frames
*
-Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
-
-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.
+ Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
+
+ 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.
*/
@@ -43,41 +43,55 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
#include "DmocMotorController.h"
-extern bool runThrottle; //TODO: remove use of global variables !
-long ms;
-
-DmocMotorController::DmocMotorController() : MotorController() {
- prefsHandler = new PrefHandler(DMOC645);
- step = SPEED_TORQUE;
-
- selectedGear = NEUTRAL;
- operationState = DISABLED;
- actualState = DISABLED;
- online = 0;
- activityCount = 0;
-// maxTorque = 2000;
- commonName = "DMOC645 Inverter";
+DmocMotorController::DmocMotorController() : MotorController()
+{
+ prefsHandler = new PrefHandler(DMOC645);
+
+ step = SPEED_TORQUE;
+ alive = 0;
+ commonName = "DMOC645 Inverter";
}
-void DmocMotorController::setup() {
- TickHandler::getInstance()->detach(this);
+void DmocMotorController::setup()
+{
+ MotorController::setup(); // run the parent class version of this function
- Logger::info("add device: DMOC645 (id:%X, %X)", DMOC645, this);
+ // register ourselves as observer of 0x23x and 0x65x can frames
+ canHandlerEv.attach(this, DMOC_CAN_MASKED_ID_1, DMOC_CAN_MASK_1, false);
+ canHandlerEv.attach(this, DMOC_CAN_MASKED_ID_2, DMOC_CAN_MASK_2, false);
- loadConfiguration();
- MotorController::setup(); // run the parent class version of this function
+ tickHandler.attach(this, CFG_TICK_INTERVAL_MOTOR_CONTROLLER_DMOC);
+}
- // register ourselves as observer of 0x23x and 0x65x can frames
- CanHandler::getInstanceEV()->attach(this, 0x230, 0x7f0, false);
- CanHandler::getInstanceEV()->attach(this, 0x650, 0x7f0, false);
+/**
+ * Tear down the controller in a safe way.
+ */
+void DmocMotorController::tearDown()
+{
+ MotorController::tearDown();
- running = false;
- setPowerMode(modeTorque);
- setSelectedGear(NEUTRAL);
- setOpState(DISABLED );
- ms=millis();
+ canHandlerEv.detach(this, DMOC_CAN_MASKED_ID_1, DMOC_CAN_MASK_1);
+ canHandlerEv.detach(this, DMOC_CAN_MASKED_ID_2, DMOC_CAN_MASK_2);
- TickHandler::getInstance()->attach(this, CFG_TICK_INTERVAL_MOTOR_CONTROLLER_DMOC);
+ sendCmd1();
+ sendCmd2();
+ sendCmd3();
+}
+
+/**
+ * act on messages the super-class does not react upon, like state change
+ * to ready or running which should enable/disable the power-stage of the controller
+ */
+void DmocMotorController::handleStateChange(Status::SystemState oldState, Status::SystemState newState)
+{
+ MotorController::handleStateChange(oldState, newState);
+
+ // for safety reasons at power off first request 0 torque - this allows the controller to dissipate residual fields first
+ if (!powerOn) {
+ sendCmd1();
+ sendCmd2();
+ sendCmd3();
+ }
}
/*
@@ -88,355 +102,264 @@ void DmocMotorController::setup() {
everything has gone according to plan.
*/
-void DmocMotorController::handleCanFrame(CAN_FRAME *frame) {
- int RotorTemp, invTemp, StatorTemp;
- int temp;
- online = 1; //if a frame got to here then it passed the filter and must have been from the DMOC
-
- Logger::debug("DMOC CAN received: %X %X %X %X %X %X %X %X %X", frame->id,frame->data.bytes[0] ,frame->data.bytes[1],frame->data.bytes[2],frame->data.bytes[3],frame->data.bytes[4],frame->data.bytes[5],frame->data.bytes[6],frame->data.bytes[70]);
-
-
- switch (frame->id) {
- case 0x651: //Temperature status
- RotorTemp = frame->data.bytes[0];
- invTemp = frame->data.bytes[1];
- StatorTemp = frame->data.bytes[2];
- temperatureInverter = (invTemp-40) *10;
- //now pick highest of motor temps and report it
- if (RotorTemp > StatorTemp) {
- temperatureMotor = (RotorTemp-40) *10;
- }
- else {
- temperatureMotor = (StatorTemp-40) *10;
- }
- activityCount++;
- break;
- case 0x23A: //torque report
- torqueActual = ((frame->data.bytes[0] * 256) + frame->data.bytes[1]) - 30000;
- activityCount++;
- break;
-
- case 0x23B: //speed and current operation status
- speedActual = abs(((frame->data.bytes[0] * 256) + frame->data.bytes[1]) - 20000);
- temp = (OperationState) (frame->data.bytes[6] >> 4);
- //actually, the above is an operation status report which doesn't correspond
- //to the state enum so translate here.
- switch (temp) {
-
- case 0: //Initializing
- actualState = DISABLED;
- faulted=false;
- break;
-
- case 1: //disabled
- actualState = DISABLED;
- faulted=false;
- break;
-
- case 2: //ready (standby)
- actualState = STANDBY;
- faulted=false;
- ready = true;
- break;
-
- case 3: //enabled
- actualState = ENABLE;
- faulted=false;
- break;
-
- case 4: //Power Down
- actualState = POWERDOWN;
- faulted=false;
- break;
-
- case 5: //Fault
- actualState = DISABLED;
- faulted=true;
- break;
-
- case 6: //Critical Fault
- actualState = DISABLED;
- faulted=true;
- break;
-
- case 7: //LOS
- actualState = DISABLED;
- faulted=true;
- break;
- }
- Logger::debug("OpState: %d", temp);
- activityCount++;
- break;
-
- //case 0x23E: //electrical status
- //gives volts and amps for D and Q but does the firmware really care?
- //break;
-
- case 0x650: //HV bus status
- dcVoltage = ((frame->data.bytes[0] * 256) + frame->data.bytes[1]);
- dcCurrent = ((frame->data.bytes[2] * 256) + frame->data.bytes[3]) - 5000; //offset is 500A, unit = .1A
- activityCount++;
- break;
- }
+void DmocMotorController::handleCanFrame(CAN_FRAME *frame)
+{
+ int invTemp, rotorTemp, statorTemp, actualState;
+
+ switch (frame->id) {
+ case DMOC_CAN_ID_TEMPERATURE:
+ rotorTemp = frame->data.bytes[0];
+ invTemp = frame->data.bytes[1];
+ statorTemp = frame->data.bytes[2];
+ temperatureController = (invTemp - 40) * 10;
+ temperatureMotor = (max(rotorTemp, statorTemp) - 40) * 10;
+ reportActivity();
+ break;
+
+ case DMOC_CAN_ID_TORQUE:
+ torqueActual = ((frame->data.bytes[0] * 256) + frame->data.bytes[1]) - 30000;
+ reportActivity();
+ break;
+
+ case DMOC_CAN_ID_STATUS:
+ speedActual = abs(((frame->data.bytes[0] * 256) + frame->data.bytes[1]) - 20000);
+
+ // 0: Initializing, 1: disabled, 2: ready (standby), 3: enabled, 4: Power Down
+ // 5: Fault, 6: Critical Fault, 7: LOS
+ actualState = frame->data.bytes[6] >> 4;
+ if (actualState == 2 || actualState == 3) {
+ ready = true;
+ running = (actualState == 3 ? true : false);
+ } else {
+ if (ready || running) {
+ switch (actualState) {
+ case 5:
+ logger.error(this, "Inverter reports fault");
+ break;
+ case 6:
+ logger.error(this, "Inverter reports critical fault");
+ break;
+ case 7:
+ logger.error(this, "Inverter reports LOS");
+ break;
+ }
+ }
+ ready = false;
+ running = false;
+ }
+ reportActivity();
+ break;
+
+ //case 0x23E: //electrical status
+ //gives volts and amps for D and Q but does the firmware really care?
+ //break;
+
+ case DMOC_CAN_ID_HV_STATUS:
+ dcVoltage = ((frame->data.bytes[0] * 256) + frame->data.bytes[1]);
+ dcCurrent = ((frame->data.bytes[2] * 256) + frame->data.bytes[3]) - 5000; //offset is 500A, unit = .1A
+ reportActivity();
+ break;
+ }
}
/*Do note that the DMOC expects all three command frames and it expect them to happen at least twice a second. So, probably it'd be ok to essentially
rotate through all of them, one per tick. That gives us a time frame of 30ms for each command frame. That should be plenty fast.
-*/
-void DmocMotorController::handleTick() {
-
- MotorController::handleTick(); //kick the ball up to papa
-
- if (activityCount > 0)
- {
- activityCount--;
- if (activityCount > 60) activityCount = 60;
- if (activityCount > 40) //If we are receiving regular CAN messages from DMOC, this will very quickly get to over 40. We'll limit
- // it to 60 so if we lose communications, within 20 ticks we will decrement below this value.
- {
- Logger::debug("EnableIn=%i and ReverseIn = %i" ,getEnableIn(),getReverseIn());
- if(getEnableIn()<0)setOpState(ENABLE); //If we HAVE an enableinput 0-3, we'll let that handle opstate. Otherwise set it to ENABLE
- if(getReverseIn()<0)setSelectedGear(DRIVE); //If we HAVE a reverse input, we'll let that determine forward/reverse. Otherwise set it to DRIVE
- }
- }
- else {
- setSelectedGear(NEUTRAL); //We will stay in NEUTRAL until we get at least 40 frames ahead indicating continous communications.
- }
-
- if (millis()-ms>2000 && online==0)
- {
- running=false; // We haven't received any frames for over 2 seconds. Otherwise online would be 1.
- ms=millis(); //So we've lost communications. Let's turn off the running light.
- }
- running=online;
- online=0;//This flag will be set to 1 by received frames.
-
- sendCmd1(); //This actually sets our GEAR and our actualstate cycle
- sendCmd2(); //This is our torque command
- sendCmd3();
- //sendCmd4(); //These appear to be not needed.
- //sendCmd5(); //But we'll keep them for future reference
-
-
+ */
+void DmocMotorController::handleTick()
+{
+ MotorController::handleTick();
+
+ step = CHAL_RESP;
+ sendCmd1();
+ sendCmd2();
+ sendCmd3();
}
//Commanded RPM plus state of key and gear selector
-void DmocMotorController::sendCmd1() {
- DmocMotorControllerConfiguration *config = (DmocMotorControllerConfiguration *)getConfiguration();
- CAN_FRAME output;
- OperationState newstate;
- alive = (alive + 2) & 0x0F;
- output.length = 8;
- output.id = 0x232;
- output.extended = 0; //standard frame
- output.rtr = 0;
-
- if (throttleRequested > 0 && operationState == ENABLE && selectedGear != NEUTRAL && powerMode == modeSpeed)
- speedRequested = 20000 + (((long) throttleRequested * (long) config->speedMax) / 1000);
- else
- speedRequested = 20000;
- output.data.bytes[0] = (speedRequested & 0xFF00) >> 8;
- output.data.bytes[1] = (speedRequested & 0x00FF);
- output.data.bytes[2] = 0; //not used
- output.data.bytes[3] = 0; //not used
- output.data.bytes[4] = 0; //not used
- output.data.bytes[5] = ON; //key state
-
- //handle proper state transitions
- newstate = DISABLED;
- if (actualState == DISABLED && (operationState == STANDBY || operationState == ENABLE))
- newstate = STANDBY;
- if ((actualState == STANDBY || actualState == ENABLE) && operationState == ENABLE)
- newstate = ENABLE;
- if (operationState == POWERDOWN)
- newstate = POWERDOWN;
-
- if (actualState == ENABLE) {
- output.data.bytes[6] = alive + ((byte) selectedGear << 4) + ((byte) newstate << 6); //use new automatic state system.
- }
- else { //force neutral gear until the system is enabled.
- output.data.bytes[6] = alive + ((byte) NEUTRAL << 4) + ((byte) newstate << 6); //use new automatic state system.
- }
-
- output.data.bytes[7] = calcChecksum(output);
-
- CanHandler::getInstanceEV()->sendFrame(output);
+void DmocMotorController::sendCmd1()
+{
+ DmocMotorControllerConfiguration *config = (DmocMotorControllerConfiguration *) getConfiguration();
+ OperationState newstate;
+ CAN_FRAME output;
+
+ canHandlerEv.prepareOutputFrame(&output, DMOC_CAN_ID_COMMAND);
+ alive = (alive + 2) & 0x0F;
+
+ uint16_t speedCommand = 20000;
+ if (getSpeedRequested() != 0 && powerOn && running && getGear() != GEAR_NEUTRAL && config->powerMode == modeSpeed) {
+ speedCommand += getSpeedRequested();
+ }
+
+ output.data.bytes[0] = (speedCommand & 0xFF00) >> 8;
+ output.data.bytes[1] = (speedCommand & 0x00FF);
+ output.data.bytes[5] = ON; //key state
+
+ //handle proper state transitions
+ newstate = DISABLE;
+ if (!ready && powerOn) {
+ newstate = STANDBY;
+ }
+ if ((ready || running) && powerOn) {
+ newstate = ENABLE;
+ }
+ if (!powerOn) {
+ newstate = POWERDOWN;
+ }
+
+ Gears gear = getGear();
+ if (running) {
+ if(config->invertDirection) {
+ gear = (gear == GEAR_DRIVE ? GEAR_REVERSE : GEAR_DRIVE);
+ }
+ } else { //force neutral gear until the system is enabled.
+ gear = GEAR_NEUTRAL;
+ }
+
+ output.data.bytes[6] = alive + ((byte) gear << 4) + ((byte) newstate << 6);
+
+ output.data.bytes[7] = calcChecksum(output);
+
+ canHandlerEv.sendFrame(output);
}
//Torque limits
-void DmocMotorController::sendCmd2() {
- DmocMotorControllerConfiguration *config = (DmocMotorControllerConfiguration *)getConfiguration();
- CAN_FRAME output;
- output.length = 8;
- output.id = 0x233;
- output.extended = 0; //standard frame
- output.rtr = 0;
- //30000 is the base point where torque = 0
- //MaxTorque is in tenths like it should be.
- //Requested throttle is [-1000, 1000]
- //data 0-1 is upper limit, 2-3 is lower limit. They are set to same value to lock torque to this value
- //torqueRequested = 30000L + (((long)throttleRequested * (long)MaxTorque) / 1000L);
-
- torqueCommand = 30000; //set offset for zero torque commanded
-
- torqueRequested=0;
- if (actualState == ENABLE) { //don't even try sending torque commands until the DMOC reports it is ready
- if (selectedGear == DRIVE)
- torqueRequested = (((long) throttleRequested * (long) config->torqueMax) / 1000L);
- if (selectedGear == REVERSE)
- torqueRequested = (((long) throttleRequested * -1 *(long) config->torqueMax) / 1000L);//If reversed, regen becomes positive torque and positive pedal becomes regen. Let's reverse this by reversing the sign. In this way, we'll have gradually diminishing positive torque (in reverse, regen) followed by gradually increasing regen (positive torque in reverse.)
- }
-
- if(speedActual < config->speedMax){torqueCommand+=torqueRequested;} //If actual rpm is less than max rpm, add torque to offset
- else {torqueCommand += torqueRequested /1.3;} // else torque is halved
- output.data.bytes[0] = (torqueCommand & 0xFF00) >> 8;
- output.data.bytes[1] = (torqueCommand & 0x00FF);
- output.data.bytes[2] = output.data.bytes[0];
- output.data.bytes[3] = output.data.bytes[1];
-
- //what the hell is standby torque? Does it keep the transmission spinning for automatics? I don't know.
- output.data.bytes[4] = 0x75; //msb standby torque. -3000 offset, 0.1 scale. These bytes give a standby of 0Nm
- output.data.bytes[5] = 0x30; //lsb
- output.data.bytes[6] = alive;
- output.data.bytes[7] = calcChecksum(output);
-
- //Logger::debug("max torque: %i", maxTorque);
-
- //Logger::debug("requested torque: %i",(((long) throttleRequested * (long) maxTorque) / 1000L));
-
- CanHandler::getInstanceEV()->sendFrame(output);
- timestamp();
- Logger::debug("Torque command: MSB: %X LSB: %X %X %X %X %X %X CRC: %X %d:%d:%d.%d",output.data.bytes[0],
-output.data.bytes[1],output.data.bytes[2],output.data.bytes[3],output.data.bytes[4],output.data.bytes[5],output.data.bytes[6],output.data.bytes[7], hours, minutes, seconds, milliseconds);
-
+void DmocMotorController::sendCmd2()
+{
+ DmocMotorControllerConfiguration *config = (DmocMotorControllerConfiguration *) getConfiguration();
+ CAN_FRAME output;
+
+ canHandlerEv.prepareOutputFrame(&output, DMOC_CAN_ID_LIMIT);
+
+ if (config->powerMode == modeTorque) {
+ //30000 is the base point where torque = 0
+ //torqueRequested and torqueMax is in tenths Nm like it should be.
+ uint16_t torqueCommand = 3000; //set offset for zero torque commanded
+ if (running) { //don't even try sending torque commands until the DMOC reports it is ready
+ int16_t torqueRequested = (speedActual < config->speedMax ? getTorqueRequested() : getTorqueRequested() / 1.3);
+
+ if ((config->invertDirection ^ getGear()) == GEAR_REVERSE) {
+ torqueRequested *= -1;
+ }
+ torqueCommand += torqueRequested;
+ }
+
+ //data 0-1 is upper limit, 2-3 is lower limit. They are set to same value to lock torque to this value
+ output.data.bytes[0] = (torqueCommand & 0xFF00) >> 8;
+ output.data.bytes[1] = (torqueCommand & 0x00FF);
+ output.data.bytes[2] = output.data.bytes[0];
+ output.data.bytes[3] = output.data.bytes[1];
+ } else { //RPM mode so request max torque as upper limit and zero torque as lower limit
+ output.data.bytes[0] = ((30000L + config->torqueMax) & 0xFF00) >> 8;
+ output.data.bytes[1] = ((30000L + config->torqueMax) & 0x00FF);
+ output.data.bytes[2] = 0x75;
+ output.data.bytes[3] = 0x30;
+ }
+
+ //what the hell is standby torque? Does it keep the transmission spinning for automatics? I don't know.
+ output.data.bytes[4] = 0x75; //msb standby torque. -3000 offset, 0.1 scale. These bytes give a standby of 0Nm
+ output.data.bytes[5] = 0x30; //lsb
+ output.data.bytes[6] = alive;
+ output.data.bytes[7] = calcChecksum(output);
+
+ canHandlerEv.sendFrame(output);
}
//Power limits plus setting ambient temp and whether to cool power train or go into limp mode
-void DmocMotorController::sendCmd3() {
- CAN_FRAME output;
- output.length = 8;
- output.id = 0x234;
- output.extended = 0; //standard frame
- output.rtr = 0;
-
- int regenCalc = 65000 - (MaxRegenWatts / 4);
- int accelCalc = (MaxAccelWatts / 4);
- output.data.bytes[0] = ((regenCalc & 0xFF00) >> 8); //msb of regen watt limit
- output.data.bytes[1] = (regenCalc & 0xFF); //lsb
- output.data.bytes[2] = ((accelCalc & 0xFF00) >> 8); //msb of acceleration limit
- output.data.bytes[3] = (accelCalc & 0xFF); //lsb
- output.data.bytes[4] = 0; //not used
- output.data.bytes[5] = 60; //20 degrees celsius
- output.data.bytes[6] = alive;
- output.data.bytes[7] = calcChecksum(output);
-
- CanHandler::getInstanceEV()->sendFrame(output);
+void DmocMotorController::sendCmd3()
+{
+ DmocMotorControllerConfiguration *config = (DmocMotorControllerConfiguration *) getConfiguration();
+ CAN_FRAME output;
+ canHandlerEv.prepareOutputFrame(&output, DMOC_CAN_ID_LIMIT2);
+
+ int regenCalc = 65000 - (config->maxMechanicalPowerRegen * 25);
+ int accelCalc = (config->maxMechanicalPowerMotor * 25);
+ output.data.bytes[0] = ((regenCalc & 0xFF00) >> 8); //msb of regen watt limit
+ output.data.bytes[1] = (regenCalc & 0xFF); //lsb
+ output.data.bytes[2] = ((accelCalc & 0xFF00) >> 8); //msb of acceleration limit
+ output.data.bytes[3] = (accelCalc & 0xFF); //lsb
+ output.data.bytes[4] = 0; //not used
+ output.data.bytes[5] = 60; //20 degrees celsius
+ output.data.bytes[6] = alive;
+ output.data.bytes[7] = calcChecksum(output);
+
+ canHandlerEv.sendFrame(output);
}
//challenge/response frame 1 - Really doesn't contain anything we need I dont think
-void DmocMotorController::sendCmd4() {
- CAN_FRAME output;
- output.length = 8;
- output.id = 0x235;
- output.extended = 0; //standard frame
- output.rtr = 0;
- output.data.bytes[0] = 37; //i don't know what all these values are
- output.data.bytes[1] = 11; //they're just copied from real traffic
- output.data.bytes[2] = 0;
- output.data.bytes[3] = 0;
- output.data.bytes[4] = 6;
- output.data.bytes[5] = 1;
- output.data.bytes[6] = alive;
- output.data.bytes[7] = calcChecksum(output);
-
- CanHandler::getInstanceEV()->sendFrame(output);
+void DmocMotorController::sendCmd4()
+{
+ CAN_FRAME output;
+ canHandlerEv.prepareOutputFrame(&output, DMOC_CAN_ID_CHALLENGE);
+ output.data.bytes[0] = 37; //i don't know what all these values are
+ output.data.bytes[1] = 11; //they're just copied from real traffic
+ output.data.bytes[4] = 6;
+ output.data.bytes[5] = 1;
+ output.data.bytes[6] = alive;
+ output.data.bytes[7] = calcChecksum(output);
+
+ canHandlerEv.sendFrame(output);
}
//Another C/R frame but this one also specifies which shifter position we're in
-void DmocMotorController::sendCmd5() {
- CAN_FRAME output;
- output.length = 8;
- output.id = 0x236;
- output.extended = 0; //standard frame
- output.rtr = 0;
- output.data.bytes[0] = 2;
- output.data.bytes[1] = 127;
- output.data.bytes[2] = 0;
- if (operationState == ENABLE && selectedGear != NEUTRAL) {
- output.data.bytes[3] = 52;
- output.data.bytes[4] = 26;
- output.data.bytes[5] = 59; //drive
- }
- else {
- output.data.bytes[3] = 39;
- output.data.bytes[4] = 19;
- output.data.bytes[5] = 55; //neutral
- }
- //--PRND12
- output.data.bytes[6] = alive;
- output.data.bytes[7] = calcChecksum(output);
-
- CanHandler::getInstanceEV()->sendFrame(output);
-}
+void DmocMotorController::sendCmd5()
+{
+ CAN_FRAME output;
+ canHandlerEv.prepareOutputFrame(&output, DMOC_CAN_ID_CHALLENGE2);
+ output.data.bytes[0] = 2;
+ output.data.bytes[1] = 127;
+
+ if (powerOn && getGear() != GEAR_NEUTRAL) {
+ output.data.bytes[3] = 52;
+ output.data.bytes[4] = 26;
+ output.data.bytes[5] = 59; //drive
+ } else {
+ output.data.bytes[3] = 39;
+ output.data.bytes[4] = 19;
+ output.data.bytes[5] = 55; //neutral
+ }
+ //--PRND12
+ output.data.bytes[6] = alive;
+ output.data.bytes[7] = calcChecksum(output);
-void DmocMotorController::setGear(Gears gear) {
- selectedGear = gear;
- //if the gear was just set to drive or reverse and the DMOC is not currently in enabled
- //op state then ask for it by name
- if (selectedGear != NEUTRAL) {
- operationState = ENABLE;
- }
- //should it be set to standby when selecting neutral? I don't know. Doing that prevents regen
- //when in neutral and I don't think people will like that.
+ canHandlerEv.sendFrame(output);
}
//this might look stupid. You might not believe this is real. It is. This is how you
//calculate the checksum for the DMOC frames.
-byte DmocMotorController::calcChecksum(CAN_FRAME thisFrame) {
- byte cs;
- byte i;
- cs = thisFrame.id;
- for (i = 0; i < 7; i++)
- cs += thisFrame.data.bytes[i];
- i = cs + 3;
- cs = ((int) 256 - i);
- return cs;
-}
+byte DmocMotorController::calcChecksum(CAN_FRAME thisFrame)
+{
+ byte cs;
+ byte i;
+ cs = thisFrame.id;
+
+ for (i = 0; i < 7; i++) {
+ cs += thisFrame.data.bytes[i];
+ }
-DeviceId DmocMotorController::getId() {
- return (DMOC645);
+ i = cs + 3;
+ cs = ((int) 256 - i);
+ return cs;
}
-uint32_t DmocMotorController::getTickInterval()
+DeviceId DmocMotorController::getId()
{
- return CFG_TICK_INTERVAL_MOTOR_CONTROLLER_DMOC;
+ return (DMOC645);
}
-void DmocMotorController::loadConfiguration() {
- DmocMotorControllerConfiguration *config = (DmocMotorControllerConfiguration *)getConfiguration();
-
- if (!config) {
- config = new DmocMotorControllerConfiguration();
- setConfiguration(config);
- }
+void DmocMotorController::loadConfiguration()
+{
+ DmocMotorControllerConfiguration *config = (DmocMotorControllerConfiguration *) getConfiguration();
- MotorController::loadConfiguration(); // call parent
-}
+ if (!config) {
+ config = new DmocMotorControllerConfiguration();
+ setConfiguration(config);
+ }
-void DmocMotorController::saveConfiguration() {
- MotorController::saveConfiguration();
+ MotorController::loadConfiguration(); // call parent
}
-void DmocMotorController::timestamp()
+void DmocMotorController::saveConfiguration()
{
- milliseconds = (int) (millis()/1) %1000 ;
- seconds = (int) (millis() / 1000) % 60 ;
- minutes = (int) ((millis() / (1000*60)) % 60);
- hours = (int) ((millis() / (1000*60*60)) % 24);
- // char buffer[9];
- //sprintf(buffer,"%02d:%02d:%02d.%03d", hours, minutes, seconds, milliseconds);
- // Serial<
#include "config.h"
#include "MotorController.h"
-#include "sys_io.h"
+#include "SystemIO.h"
#include "TickHandler.h"
-#include "CanHandler.h"
+
+// CAN bus id's for frames sent to DMOC
+
+#define DMOC_CAN_ID_COMMAND 0x232 // send commands (speed, gear)
+#define DMOC_CAN_ID_LIMIT 0x233 // send limitations (torque)
+#define DMOC_CAN_ID_LIMIT2 0x234 // send limitations (power)
+#define DMOC_CAN_ID_CHALLENGE 0x235 // send challenge/response
+#define DMOC_CAN_ID_CHALLENGE2 0x236 // send challenge/response
+
+// CAN bus id's for frames received from DMOC
+
+#define DMOC_CAN_ID_TORQUE 0x23a // receive actual torque values 01000111010
+#define DMOC_CAN_ID_STATUS 0x23b // receive status and speed information 01000111011
+#define DMOC_CAN_MASK_1 0x7fe // mask for above id's 11111111110
+#define DMOC_CAN_MASKED_ID_1 0x23a // masked id for id's from 0x26a to 0x26f 01000111010
+
+#define DMOC_CAN_ID_HV_STATUS 0x650 // receive hv bus status information 11001010000
+#define DMOC_CAN_ID_TEMPERATURE 0x651 // receive actual temperature 11001010001
+#define DMOC_CAN_MASK_2 0x7fe // mask for above id's 11111111110
+#define DMOC_CAN_MASKED_ID_2 0x650 // masked id for id's from 0x26a to 0x26f 11001010000
/*
* Class for DMOC specific configuration parameters
*/
-class DmocMotorControllerConfiguration : public MotorControllerConfiguration {
+class DmocMotorControllerConfiguration : public MotorControllerConfiguration
+{
public:
};
-class DmocMotorController: public MotorController, CanObserver {
+class DmocMotorController: public MotorController
+{
public:
- enum Step {
- SPEED_TORQUE,
- CHAL_RESP
- };
-
- enum KeyState {
- OFF = 0,
- ON = 1,
- RESERVED = 2,
- NOACTION = 3
- };
-
-
+ enum Step {
+ SPEED_TORQUE,
+ CHAL_RESP
+ };
+
+ enum KeyState {
+ OFF = 0,
+ ON = 1,
+ RESERVED = 2,
+ NOACTION = 3
+ };
+
+ enum OperationState {
+ DISABLE = 0,
+ STANDBY = 1,
+ ENABLE = 2,
+ POWERDOWN = 3
+ };
public:
- virtual void handleTick();
- virtual void handleCanFrame(CAN_FRAME *frame);
- virtual void setup();
- void setGear(Gears gear);
+ virtual void handleTick();
+ virtual void handleCanFrame(CAN_FRAME *frame);
+ void handleStateChange(Status::SystemState, Status::SystemState);
+ virtual void setup();
+ virtual void tearDown();
- DmocMotorController();
- DeviceId getId();
- uint32_t getTickInterval();
+ DmocMotorController();
+ DeviceId getId();
- virtual void loadConfiguration();
- virtual void saveConfiguration();
+ virtual void loadConfiguration();
+ virtual void saveConfiguration();
private:
-
- OperationState actualState; //what the controller is reporting it is
- int step;
- byte online; //counter for whether DMOC appears to be operating
- byte alive;
- int activityCount;
- uint16_t torqueCommand;
- void timestamp();
-
- void sendCmd1();
- void sendCmd2();
- void sendCmd3();
- void sendCmd4();
- void sendCmd5();
- byte calcChecksum(CAN_FRAME thisFrame);
+ int step;
+ byte alive;
+
+ void sendCmd1();
+ void sendCmd2();
+ void sendCmd3();
+ void sendCmd4();
+ void sendCmd5();
+ byte calcChecksum(CAN_FRAME thisFrame);
};
diff --git a/ELM327Processor.cpp b/ELM327Processor.cpp
index 5185147..8e84916 100644
--- a/ELM327Processor.cpp
+++ b/ELM327Processor.cpp
@@ -1,110 +1,124 @@
#include "ELM327Processor.h"
-ELM327Processor::ELM327Processor() {
- obd2Handler = OBD2Handler::getInstance();
+ELM327Processor::ELM327Processor()
+{
+ obd2Handler = OBD2Handler::getInstance();
+ bHeader = false;
+ bLineFeed = false;
}
-String ELM327Processor::processELMCmd(char *cmd) {
- String retString = String();
- String lineEnding;
- if (bLineFeed) lineEnding = String("\r\n");
- else lineEnding = String("\r");
+String ELM327Processor::generateUpdate()
+{
+ return "";
+}
+
+String ELM327Processor::generateLogEntry(String logLevel, String deviceName, String message)
+{
+ return "";
+}
+
+String ELM327Processor::processInput(char *cmd)
+{
+ String retString = String();
+ String lineEnding;
+
+ for (char *p = cmd; *p; p++) {
+ *p = tolower(*p);
+ }
+
+ if (bLineFeed) {
+ lineEnding = String("\r\n");
+ } else {
+ lineEnding = String("\r");
+ }
+
+ if (!strncmp(cmd, "at", 2)) {
+
+ if (!strcmp(cmd, "atz")) { //reset hardware
+ retString.concat(lineEnding);
+ retString.concat("ELM327 v1.3a");
+ } else if (!strncmp(cmd, "atsh", 4)) { //set header address
+ //ignore this - just say OK
+ retString.concat("OK");
+ } else if (!strncmp(cmd, "ate", 3)) { //turn echo on/off
+ //could support echo but I don't see the need, just ignore this
+ retString.concat("OK");
+ } else if (!strncmp(cmd, "ath", 3)) { //turn headers on/off
+ if (cmd[3] == '1') {
+ bHeader = true;
+ } else {
+ bHeader = false;
+ }
+
+ retString.concat("OK");
+ } else if (!strncmp(cmd, "atl", 3)) { //turn linefeeds on/off
+ if (cmd[3] == '1') {
+ bLineFeed = true;
+ } else {
+ bLineFeed = false;
+ }
+
+ retString.concat("OK");
+ } else if (!strcmp(cmd, "at@1")) { //send device description
+ retString.concat("ELM327 Emulator");
+ } else if (!strcmp(cmd, "ati")) { //send chip ID
+ retString.concat("ELM327 v1.3a");
+ } else if (!strncmp(cmd, "atat", 4)) { //set adaptive timing
+ //don't intend to support adaptive timing at all
+ retString.concat("OK");
+ } else if (!strncmp(cmd, "atsp", 4)) { //set protocol
+ //theoretically we can ignore this
+ retString.concat("OK");
+ } else if (!strcmp(cmd, "atdp")) { //show description of protocol
+ retString.concat("can11/500");
+ } else if (!strcmp(cmd, "atdpn")) { //show protocol number (same as passed to sp)
+ retString.concat("6");
+ } else if (!strcmp(cmd, "atd")) { //set to defaults
+ retString.concat("OK");
+ } else if (!strncmp(cmd, "atm", 3)) { //turn memory on/off
+ retString.concat("OK");
+ } else if (!strcmp(cmd, "atrv")) { //show 12v rail voltage
+ //TODO: the system should actually have this value so it wouldn't hurt to
+ //look it up and report the real value.
+ retString.concat("14.2V");
+ } else { //by default respond to anything not specifically handled by just saying OK and pretending.
+ retString.concat("OK");
+ }
+ } else { //if no AT then assume it is a PID request. This takes the form of four bytes which form the alpha hex digit encoding for two bytes
+ //there should be four or six characters here forming the ascii representation of the PID request. Easiest for now is to turn the ascii into
+ //a 16 bit number and mask off to get the bytes
+ if (strlen(cmd) == 4) {
+ uint32_t valu = strtol((char *) cmd, NULL, 16); //the pid format is always in hex
+ byte in[] = { 2, ((valu >> 8) & 0xFF), (valu & 0xFF) };
+ byte out[7];
+ char buff[10];
+
+ if (obd2Handler->processRequest(in, out)) {
+ if (bHeader) {
+ retString.concat("7E8");
+ out[0] += 2; //not sending only data bits but mode and pid too
- if (!strncmp(cmd, "at", 2)) {
+ for (int i = 0; i <= out[0]; i++) {
+ sprintf(buff, "%02X", out[i]);
+ retString.concat(buff);
+ }
+ } else {
+ sprintf(buff, "%02X", out[1]);
+ retString.concat(buff);
+ sprintf(buff, "%02X", out[2]);
+ retString.concat(buff);
- if (!strcmp(cmd, "atz")) { //reset hardware
- retString.concat(lineEnding);
- retString.concat("ELM327 v1.3a");
- }
- else if (!strncmp(cmd, "atsh",4)) { //set header address
- //ignore this - just say OK
- retString.concat("OK");
- }
- else if (!strncmp(cmd, "ate",3)) { //turn echo on/off
- //could support echo but I don't see the need, just ignore this
- retString.concat("OK");
- }
- else if (!strncmp(cmd, "ath",3)) { //turn headers on/off
- if (cmd[3] == '1') bHeader = true;
- else bHeader = false;
- retString.concat("OK");
- }
- else if (!strncmp(cmd, "atl",3)) { //turn linefeeds on/off
- if (cmd[3] == '1') bLineFeed = true;
- else bLineFeed = false;
- retString.concat("OK");
- }
- else if (!strcmp(cmd, "at@1")) { //send device description
- retString.concat("ELM327 Emulator");
- }
- else if (!strcmp(cmd, "ati")) { //send chip ID
- retString.concat("ELM327 v1.3a");
- }
- else if (!strncmp(cmd, "atat",4)) { //set adaptive timing
- //don't intend to support adaptive timing at all
- retString.concat("OK");
- }
- else if (!strncmp(cmd, "atsp",4)) { //set protocol
- //theoretically we can ignore this
- retString.concat("OK");
- }
- else if (!strcmp(cmd, "atdp")) { //show description of protocol
- retString.concat("can11/500");
- }
- else if (!strcmp(cmd, "atdpn")) { //show protocol number (same as passed to sp)
- retString.concat("6");
- }
- else if (!strcmp(cmd, "atd")) { //set to defaults
- retString.concat("OK");
- }
- else if (!strncmp(cmd, "atm", 3)) { //turn memory on/off
- retString.concat("OK");
- }
- else if (!strcmp(cmd, "atrv")) { //show 12v rail voltage
- //TODO: the system should actually have this value so it wouldn't hurt to
- //look it up and report the real value.
- retString.concat("14.2V");
- }
- else { //by default respond to anything not specifically handled by just saying OK and pretending.
- retString.concat("OK");
- }
- }
- else { //if no AT then assume it is a PID request. This takes the form of four bytes which form the alpha hex digit encoding for two bytes
- //there should be four or six characters here forming the ascii representation of the PID request. Easiest for now is to turn the ascii into
- //a 16 bit number and mask off to get the bytes
- if (strlen(cmd) == 4) {
- uint32_t valu = strtol((char *) cmd, NULL, 16); //the pid format is always in hex
- uint8_t pidnum = (uint8_t)(valu & 0xFF);
- uint8_t mode = (uint8_t)((valu >> 8) & 0xFF);
- Logger::debug(ELM327EMU, "Mode: %i, PID: %i", mode, pidnum);
- char out[7];
- char buff[10];
- if (obd2Handler->processRequest(mode, pidnum, NULL, out)) {
- if (bHeader) {
- retString.concat("7E8");
- out[0] += 2; //not sending only data bits but mode and pid too
- for (int i = 0; i <= out[0]; i++) {
- sprintf(buff, "%02X", out[i]);
- retString.concat(buff);
- }
- }
- else {
- mode += 0x40;
- sprintf(buff, "%02X", mode);
- retString.concat(buff);
- sprintf(buff, "%02X", pidnum);
- retString.concat(buff);
- for (int i = 1; i <= out[0]; i++) {
- sprintf(buff, "%02X", out[i+2]);
- retString.concat(buff);
- }
- }
- }
- }
- }
+ for (int i = 1; i <= out[0]; i++) {
+ sprintf(buff, "%02X", out[i + 2]);
+ retString.concat(buff);
+ }
+ }
+ }
+ }
+ }
- retString.concat(lineEnding);
- retString.concat(">"); //prompt to show we're ready to receive again
+ retString.concat(lineEnding);
+ retString.concat(">"); //prompt to show we're ready to receive again
- return retString;
+ return retString;
}
diff --git a/ELM327Processor.h b/ELM327Processor.h
index 2195e17..f0225cd 100644
--- a/ELM327Processor.h
+++ b/ELM327Processor.h
@@ -3,20 +3,24 @@
#include
#include "config.h"
-#include "constants.h"
#include "Sys_Messages.h"
#include "DeviceTypes.h"
#include "OBD2Handler.h"
+#include "SocketProcessor.h"
-class ELM327Processor {
+class ELM327Processor : public SocketProcessor
+{
public:
- ELM327Processor();
- String processELMCmd(char *cmd);
+ ELM327Processor();
+ String generateUpdate();
+ String generateLogEntry(String logLevel, String deviceName, String message);
+ String processInput(char *input);
+
private:
- OBD2Handler *obd2Handler;
- char buffer[30]; // a buffer for various string conversions
- bool bLineFeed;
- bool bHeader;
+ OBD2Handler *obd2Handler;
+ char buffer[30]; // a buffer for various string conversions
+ bool bLineFeed;
+ bool bHeader;
};
-#endif
\ No newline at end of file
+#endif
diff --git a/ELM327_Emu.cpp b/ELM327_Emu.cpp
index a1c15c1..df65295 100644
--- a/ELM327_Emu.cpp
+++ b/ELM327_Emu.cpp
@@ -36,81 +36,74 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
/*
* Constructor. Assign serial interface to use for comm with bluetooth adapter we're emulating with
*/
-ELM327Emu::ELM327Emu() {
- prefsHandler = new PrefHandler(ELM327EMU);
+ELM327Emu::ELM327Emu()
+{
+ prefsHandler = new PrefHandler(ELM327EMU);
+ elmProc = new ELM327Processor();
- uint8_t sys_type;
- sysPrefs->read(EESYS_SYSTEM_TYPE, &sys_type);
- if (sys_type == 3 || sys_type == 4)
- serialInterface = &Serial2;
- else //older hardware used this instead
- serialInterface = &Serial3;
+ if (systemIO.getSystemType() == SystemIOConfiguration::GEVCU3 || SystemIOConfiguration::GEVCU4) {
+ serialInterface = &Serial2;
+ } else { //older hardware used this instead
+ serialInterface = &Serial3;
+ }
+ serialInterface->begin(9600);
- commonName = "ELM327 Emulator over Bluetooth";
-}
+ commonName = "ELM327 Emulator over Bluetooth";
-/*
- * Constructor. Pass serial interface to use
- */
-ELM327Emu::ELM327Emu(USARTClass *which) {
- prefsHandler = new PrefHandler(ELM327EMU);
- serialInterface = which;
+ ibWritePtr = 0;
}
-
/*
* Initialization of hardware and parameters
*/
-void ELM327Emu::setup() {
-
- Logger::info("add device: ELM327 emulator (id: %X, %X", ELM327EMU, this);
-
- TickHandler::getInstance()->detach(this);
-
- tickCounter = 0;
- ibWritePtr = 0;
- serialInterface->begin(9600);
-
- elmProc = new ELM327Processor();
-
- //this isn't a wifi link but the timer interval can be the same
- //because it serves a similar function and has similar timing requirements
- TickHandler::getInstance()->attach(this, CFG_TICK_INTERVAL_WIFI);
+void ELM327Emu::setup()
+{
+ ready = true;
+ running = true;
+
+ //this isn't a wifi link but the timer interval can be the same
+ //because it serves a similar function and has similar timing requirements
+ tickHandler.attach(this, CFG_TICK_INTERVAL_WIFI);
}
/*
* Send a command to ichip. The "AT+i" part will be added.
*/
-void ELM327Emu::sendCmd(String cmd) {
- serialInterface->write("AT");
- serialInterface->print(cmd);
- serialInterface->write(13);
- loop(); // parse the response
+void ELM327Emu::sendCmd(String cmd)
+{
+ serialInterface->write("AT");
+ serialInterface->print(cmd);
+ serialInterface->write(13);
+ loop(); // parse the response
}
/*
*/
-void ELM327Emu::handleTick() {
+void ELM327Emu::handleTick()
+{
}
/*
* Handle a message sent by the DeviceManager.
*/
-void ELM327Emu::handleMessage(uint32_t messageType, void* message) {
- Device::handleMessage(messageType, message);
-
- switch (messageType) {
- case MSG_SET_PARAM: {
- break;
- }
- case MSG_CONFIG_CHANGE:
- break;
- case MSG_COMMAND:
- sendCmd((char *)message);
- break;
- }
+void ELM327Emu::handleMessage(uint32_t messageType, void* message)
+{
+ Device::handleMessage(messageType, message);
+
+ switch (messageType) {
+ case MSG_SET_PARAM: {
+ break;
+ }
+
+ case MSG_CONFIG_CHANGE:
+ break;
+
+ case MSG_COMMAND:
+ sendCmd((char *) message);
+ break;
+ }
}
/*
@@ -120,67 +113,80 @@ void ELM327Emu::handleMessage(uint32_t messageType, void* message) {
* But, for now just echo stuff to our serial port for debugging
*/
-void ELM327Emu::loop() {
- int incoming;
- while (serialInterface->available()) {
- incoming = serialInterface->read();
- if (incoming != -1) { //and there is no reason it should be -1
- if (incoming == 13 || ibWritePtr > 126) { // on CR or full buffer, process the line
- incomingBuffer[ibWritePtr] = 0; //null terminate the string
- ibWritePtr = 0; //reset the write pointer
-
- if (Logger::isDebug())
- Logger::debug(ELM327EMU, incomingBuffer);
- processCmd();
-
- } else { // add more characters
- if (incoming != 10 && incoming != ' ') // don't add a LF character or spaces. Strip them right out
- incomingBuffer[ibWritePtr++] = (char)tolower(incoming); //force lowercase to make processing easier
- }
- } else
- return;
- }
+void ELM327Emu::loop()
+{
+ int incoming;
+
+ while (serialInterface->available()) {
+ incoming = serialInterface->read();
+
+ if (incoming != -1) { //and there is no reason it should be -1
+ if (incoming == 13 || ibWritePtr > 126) { // on CR or full buffer, process the line
+ incomingBuffer[ibWritePtr] = 0; //null terminate the string
+ ibWritePtr = 0; //reset the write pointer
+
+ if (logger.isDebug()) {
+ logger.debug(this, incomingBuffer);
+ }
+
+ processCmd();
+
+ } else { // add more characters
+ if (incoming != 10 && incoming != ' ') { // don't add a LF character or spaces. Strip them right out
+ incomingBuffer[ibWritePtr++] = (char) tolower(incoming); //force lowercase to make processing easier
+ }
+ }
+ } else {
+ return;
+ }
+ }
}
/*
-* There is no need to pass the string in here because it is local to the class so this function can grab it by default
-* But, for reference, this cmd processes the command in incomingBuffer
+* There is no need to pass the string in here because it is local to the class so this function can grab it by default
+* But, for reference, this cmd processes the command in incomingBuffer
*/
-void ELM327Emu::processCmd() {
- String retString = elmProc->processELMCmd(incomingBuffer);
-
- serialInterface->print(retString);
- if (Logger::isDebug()) {
- char buff[30];
- retString.toCharArray(buff, 30);
- Logger::debug(ELM327EMU, buff);
- }
-
+void ELM327Emu::processCmd()
+{
+ String retString = elmProc->processInput(incomingBuffer);
+
+ serialInterface->print(retString);
+
+ if (logger.isDebug()) {
+ char buff[30];
+ retString.toCharArray(buff, 30);
+ logger.debug(this, buff);
+ }
+
}
-DeviceType ELM327Emu::getType() {
- return DEVICE_MISC;
+DeviceType ELM327Emu::getType()
+{
+ return DEVICE_MISC;
}
-DeviceId ELM327Emu::getId() {
- return (ELM327EMU);
+DeviceId ELM327Emu::getId()
+{
+ return (ELM327EMU);
}
-void ELM327Emu::loadConfiguration() {
- ELM327Configuration *config = (ELM327Configuration *)getConfiguration();
+void ELM327Emu::loadConfiguration()
+{
+// ELM327Configuration *config = (ELM327Configuration *) getConfiguration();
- if (prefsHandler->checksumValid()) { //checksum is good, read in the values stored in EEPROM
- Logger::debug(ELM327EMU, "Valid checksum so using stored elm327 emulator config values");
- //TODO: implement processing of config params for WIFI
-// prefsHandler->read(EESYS_WIFI0_SSID, &config->ssid);
- }
+ if (prefsHandler->checksumValid()) { //checksum is good, read in the values stored in EEPROM
+ //TODO: implement processing of config params for WIFI
+// prefsHandler->read(EESYS_WIFI0_SSID, &config->ssid);
+ } else {
+ saveConfiguration();
+ }
}
-void ELM327Emu::saveConfiguration() {
- ELM327Configuration *config = (ELM327Configuration *) getConfiguration();
+void ELM327Emu::saveConfiguration()
+{
+// ELM327Configuration *config = (ELM327Configuration *) getConfiguration();
- //TODO: implement processing of config params for WIFI
-// prefsHandler->write(EESYS_WIFI0_SSID, config->ssid);
-// prefsHandler->saveChecksum();
+ //TODO: implement processing of config params for WIFI
+// prefsHandler->write(EESYS_WIFI0_SSID, config->ssid);
+ prefsHandler->saveChecksum();
}
-
\ No newline at end of file
diff --git a/ELM327_Emu.h b/ELM327_Emu.h
index b868f9c..cbd77c0 100644
--- a/ELM327_Emu.h
+++ b/ELM327_Emu.h
@@ -33,7 +33,7 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
/*
List of AT commands to support:
AT E0 (turn echo off)
-AT H (0/1) - Turn headers on or off - headers are used to determine how many ECU’s present (hint: only send one response to 0100 and emulate a single ECU system to save time coding)
+AT H (0/1) - Turn headers on or off - headers are used to determine how many ECU�s present (hint: only send one response to 0100 and emulate a single ECU system to save time coding)
AT L0 (Turn linefeeds off - just use CR)
AT Z (reset)
AT SH - Set header address - seems to set the ECU address to send to (though you may be able to ignore this if you wish)
@@ -52,47 +52,44 @@ AT RV (adapter voltage) - Send something like 14.4V
#include
#include "config.h"
-#include "constants.h"
#include "DeviceManager.h"
#include "Sys_Messages.h"
#include "DeviceTypes.h"
#include "ELM327Processor.h"
-extern PrefHandler *sysPrefs;
-
/*
* The extended configuration class with additional parameters for ichip WLAN
*/
-class ELM327Configuration : public DeviceConfiguration {
+class ELM327Configuration : public DeviceConfiguration
+{
public:
};
-class ELM327Emu : public Device {
- public:
-
+class ELM327Emu : public Device
+{
+public:
+
ELM327Emu();
ELM327Emu(USARTClass *which);
void setup(); //initialization on start up
void handleTick(); //periodic processes
void handleMessage(uint32_t messageType, void* message);
- DeviceType getType();
+ DeviceType getType();
DeviceId getId();
void loop();
- void sendCmd(String cmd);
+ void sendCmd(String cmd);
- void loadConfiguration();
- void saveConfiguration();
+ void loadConfiguration();
+ void saveConfiguration();
- private:
+private:
USARTClass *serialInterface; //Allows for retargetting which serial port we use
- ELM327Processor *elmProc;
+ ELM327Processor *elmProc;
char incomingBuffer[128]; //storage for one incoming line
- int tickCounter;
int ibWritePtr;
- int currReply;
- char buffer[30]; // a buffer for various string conversions
+ char buffer[30]; // a buffer for various string conversions
- void processCmd();
+ void processCmd();
};
#endif
diff --git a/FaultHandler.cpp b/FaultHandler.cpp
index ddc37c8..6782405 100644
--- a/FaultHandler.cpp
+++ b/FaultHandler.cpp
@@ -1,225 +1,216 @@
/*
* FaultHandler.cpp
*
-Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
+ Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
-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:
+ 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 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.
+ 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 "FaultHandler.h"
#include "eeprom_layout.h"
- FaultHandler::FaultHandler()
- {
- }
-
- void FaultHandler::setup()
- {
- TickHandler::getInstance()->detach(this);
-
- Logger::info("Initializing Fault Handler", FAULTSYS, this);
-
- loadFromEEPROM();
-
- //Use the heartbeat interval because it's slow and already exists so we can piggyback on the interrupt
- //so as to not create more timers than necessary.
- TickHandler::getInstance()->attach(this, CFG_TICK_INTERVAL_HEARTBEAT);
- }
-
-
- //Every tick update the global time and save it to EEPROM (delayed saving)
- void FaultHandler::handleTick()
- {
- globalTime = baseTime + (millis() / 100);
- memCache->Write(EE_FAULT_LOG + EEFAULT_RUNTIME, globalTime);
- }
-
- uint16_t FaultHandler::raiseFault(uint16_t device, uint16_t code, bool ongoing = false)
- {
- bool incPtr = false;
- globalTime = baseTime + (millis() / 100);
-
- //first try to see if this fault is already registered as ongoing. If so don't update the time but set ongoing status if necessary
- bool found = false;
- for (int j = 0; j < CFG_FAULT_HISTORY_SIZE; j++)
- {
- if (faultList[j].ongoing && faultList[j].device == device && faultList[j].faultCode == code)
- {
- found = true;
- //faultList[j].timeStamp = globalTime;
- faultList[j].ongoing = ongoing;
- break; //quit searching
- }
- }
-
- //nothing ongoing to register a new one
- if (!found)
- {
- faultList[faultWritePointer].timeStamp = globalTime;
- faultList[faultWritePointer].ack = false;
- faultList[faultWritePointer].device = device;
- faultList[faultWritePointer].faultCode = code;
- faultList[faultWritePointer].ongoing = ongoing;
- incPtr = true;
- }
-
- //write back to EEPROM cache
- memCache->Write(EE_FAULT_LOG + EEFAULT_FAULTS_START + sizeof(FAULT) * faultWritePointer, &faultList[faultWritePointer], sizeof(FAULT));
-
- if (incPtr)
- {
- //Cause the memory caching system to immediately write the page but only if incPtr is set (only if this is a new fault)
- memCache->InvalidateAddress(EE_FAULT_LOG + EEFAULT_FAULTS_START + sizeof(FAULT)* faultWritePointer);
- faultWritePointer = (faultWritePointer + 1) % CFG_FAULT_HISTORY_SIZE;
- memCache->Write(EE_FAULT_LOG + EEFAULT_WRITEPTR , faultWritePointer);
- //Cause the page to be immediately fully aged so that it is written very soon.
- memCache->AgeFullyAddress(EE_FAULT_LOG + EEFAULT_WRITEPTR);
- //Also announce fault on the console
- Logger::error(FAULTSYS, "Fault %x raised by device %x at uptime %i", code, device, globalTime);
- }
- }
-
- void FaultHandler::cancelOngoingFault(uint16_t device, uint16_t code)
- {
- for (int i = 0; i < CFG_FAULT_HISTORY_SIZE; i++)
- {
- if (faultList[i].ongoing && faultList[i].device == device && faultList[i].faultCode == code)
- {
- setFaultOngoing(i, false);
- }
- }
- }
-
- uint16_t FaultHandler::getFaultCount()
- {
- int count = 0;
- for (int i = 0; i < CFG_FAULT_HISTORY_SIZE; i++)
- {
- if (faultList[i].ack == false && faultList[i].device != 0xFFFF)
- {
- count++;
- }
- }
- return count;
- }
-
- //the fault handler isn't a device per se and uses more memory than a device would normally be allocated so
- //it does not use PrefHandler
- void FaultHandler::loadFromEEPROM()
- {
- uint8_t validByte;
- memCache->Read(EE_FAULT_LOG, &validByte);
- if (validByte == 0xB2) //magic byte value for a valid fault cache
- {
- memCache->Read(EE_FAULT_LOG + EEFAULT_READPTR, &faultReadPointer);
- memCache->Read(EE_FAULT_LOG + EEFAULT_WRITEPTR, &faultWritePointer);
- memCache->Read(EE_FAULT_LOG + EEFAULT_RUNTIME, &globalTime);
- baseTime = globalTime;
- for (int i = 0; i < CFG_FAULT_HISTORY_SIZE; i++)
- {
- memCache->Read(EE_FAULT_LOG + EEFAULT_FAULTS_START + sizeof(FAULT) * i, &faultList[i], sizeof(FAULT));
- }
- }
- else //reinitialize the fault cache storage
- {
- validByte = 0xB2;
- memCache->Write(EE_FAULT_LOG, validByte);
- memCache->Write(EE_FAULT_LOG + EEFAULT_READPTR, (uint16_t)0);
- memCache->Write(EE_FAULT_LOG + EEFAULT_WRITEPTR, (uint16_t)0);
- globalTime = baseTime = millis() / 100;
- memCache->Write(EE_FAULT_LOG + EEFAULT_RUNTIME, globalTime);
-
- FAULT tempFault;
- tempFault.ack = true;
- tempFault.device = 0xFFFF;
- tempFault.faultCode = 0xFFFF;
- tempFault.ongoing = false;
- tempFault.timeStamp = 0;
- for (int i = 0; i < CFG_FAULT_HISTORY_SIZE; i++)
- {
- faultList[i] = tempFault;
- }
- saveToEEPROM();
- }
- }
-
- void FaultHandler::saveToEEPROM()
- {
- memCache->Write(EE_FAULT_LOG + EEFAULT_READPTR, faultReadPointer);
- memCache->Write(EE_FAULT_LOG + EEFAULT_WRITEPTR, faultWritePointer);
- memCache->Write(EE_FAULT_LOG + EEFAULT_RUNTIME, globalTime);
- for (int i = 0; i < CFG_FAULT_HISTORY_SIZE; i++)
- {
- memCache->Write(EE_FAULT_LOG + EEFAULT_FAULTS_START + sizeof(FAULT) * i, &faultList[i], sizeof(FAULT));
- }
- }
-
- void FaultHandler::writeFaultToEEPROM(int faultnum)
- {
- if (faultnum > 0 && faultnum < CFG_FAULT_HISTORY_SIZE)
- {
- memCache->Write(EE_FAULT_LOG + EEFAULT_FAULTS_START + sizeof(FAULT) * faultnum, &faultList[faultnum], sizeof(FAULT));
- }
- }
-
- bool FaultHandler::getNextFault(FAULT *fault)
- {
- uint16_t j;
- for (int i = 0; i < CFG_FAULT_HISTORY_SIZE; i++)
- {
- j = (faultReadPointer + i + 1) % CFG_FAULT_HISTORY_SIZE;
- if (faultList[j].ack == false) {
- fault = &faultList[j];
- faultReadPointer = j;
- return true;
- }
- }
- return false;
- }
-
- bool FaultHandler::getFault(uint16_t fault, FAULT *outFault)
- {
- if (fault > 0 && fault < CFG_FAULT_HISTORY_SIZE) {
- outFault = &faultList[fault];
- return true;
- }
- return false;
- }
-
- uint16_t FaultHandler::setFaultACK(uint16_t fault)
- {
- if (fault > 0 && fault < CFG_FAULT_HISTORY_SIZE)
- {
- faultList[fault].ack = 1;
- writeFaultToEEPROM(fault);
- }
- }
-
- uint16_t FaultHandler::setFaultOngoing(uint16_t fault, bool ongoing)
- {
- if (fault > 0 && fault < CFG_FAULT_HISTORY_SIZE)
- {
- faultList[fault].ongoing = ongoing;
- writeFaultToEEPROM(fault);
- }
- }
-
- FaultHandler faultHandler;
+FaultHandler::FaultHandler()
+{
+ baseTime = 0;
+ globalTime = 0;
+ faultReadPointer = 0;
+ faultWritePointer = 0;
+}
+
+FaultHandler::~FaultHandler()
+{
+}
+
+void FaultHandler::setup()
+{
+ tickHandler.detach(this);
+
+ logger.info("Initializing Fault Handler", FAULTSYS, this);
+
+ loadFromEEPROM();
+
+ //Use the heartbeat interval because it's slow and already exists so we can piggyback on the interrupt
+ //so as to not create more timers than necessary.
+ tickHandler.attach(this, CFG_TICK_INTERVAL_HEARTBEAT);
+}
+
+//Every tick update the global time and save it to EEPROM (delayed saving)
+void FaultHandler::handleTick()
+{
+ globalTime = baseTime + (millis() / 100);
+// memCache.Write(EE_FAULT_LOG + EEFAULT_RUNTIME, globalTime);
+}
+
+void FaultHandler::raiseFault(uint16_t device, uint16_t code, bool ongoing = false)
+{
+ bool incPtr = false;
+ globalTime = baseTime + (millis() / 100);
+
+ //first try to see if this fault is already registered as ongoing. If so don't update the time but set ongoing status if necessary
+ bool found = false;
+ for (int j = 0; j < CFG_FAULT_HISTORY_SIZE; j++) {
+ if (faultList[j].ongoing && faultList[j].device == device && faultList[j].faultCode == code) {
+ found = true;
+ //faultList[j].timeStamp = globalTime;
+ faultList[j].ongoing = ongoing;
+ break; //quit searching
+ }
+ }
+
+ //nothing ongoing to register a new one
+ if (!found) {
+ faultList[faultWritePointer].timeStamp = globalTime;
+ faultList[faultWritePointer].ack = false;
+ faultList[faultWritePointer].device = device;
+ faultList[faultWritePointer].faultCode = code;
+ faultList[faultWritePointer].ongoing = ongoing;
+ incPtr = true;
+ }
+
+ //write back to EEPROM cache
+ memCache.Write(EE_FAULT_LOG + EEFAULT_FAULTS_START + sizeof(FAULT) * faultWritePointer, &faultList[faultWritePointer], sizeof(FAULT));
+
+ if (incPtr) {
+ //Cause the memory caching system to immediately write the page but only if incPtr is set (only if this is a new fault)
+ memCache.InvalidateAddress(EE_FAULT_LOG + EEFAULT_FAULTS_START + sizeof(FAULT) * faultWritePointer);
+ faultWritePointer = (faultWritePointer + 1) % CFG_FAULT_HISTORY_SIZE;
+ memCache.Write(EE_FAULT_LOG + EEFAULT_WRITEPTR, faultWritePointer);
+ //Cause the page to be immediately fully aged so that it is written very soon.
+ memCache.AgeFullyAddress(EE_FAULT_LOG + EEFAULT_WRITEPTR);
+ //Also announce fault on the console
+ logger.error("Fault %#x raised by device %#x at uptime %i", code, device, globalTime);
+ }
+}
+
+void FaultHandler::cancelOngoingFault(uint16_t device, uint16_t code)
+{
+ for (int i = 0; i < CFG_FAULT_HISTORY_SIZE; i++) {
+ if (faultList[i].ongoing && faultList[i].device == device && faultList[i].faultCode == code) {
+ setFaultOngoing(i, false);
+ }
+ }
+}
+
+uint16_t FaultHandler::getFaultCount()
+{
+ int count = 0;
+ for (int i = 0; i < CFG_FAULT_HISTORY_SIZE; i++) {
+ if (faultList[i].ack == false && faultList[i].device != 0xFFFF) {
+ count++;
+ }
+ }
+ return count;
+}
+
+//the fault handler isn't a device per se and uses more memory than a device would normally be allocated so
+//it does not use PrefHandler
+void FaultHandler::loadFromEEPROM()
+{
+ uint8_t validByte;
+ memCache.Read(EE_FAULT_LOG, &validByte);
+ if (validByte == 0xB2) //magic byte value for a valid fault cache
+ {
+ memCache.Read(EE_FAULT_LOG + EEFAULT_READPTR, &faultReadPointer);
+ memCache.Read(EE_FAULT_LOG + EEFAULT_WRITEPTR, &faultWritePointer);
+ memCache.Read(EE_FAULT_LOG + EEFAULT_RUNTIME, &globalTime);
+ baseTime = globalTime;
+ for (int i = 0; i < CFG_FAULT_HISTORY_SIZE; i++) {
+ memCache.Read(EE_FAULT_LOG + EEFAULT_FAULTS_START + sizeof(FAULT) * i, &faultList[i], sizeof(FAULT));
+ }
+ } else //reinitialize the fault cache storage
+ {
+ validByte = 0xB2;
+ memCache.Write(EE_FAULT_LOG, validByte);
+ memCache.Write(EE_FAULT_LOG + EEFAULT_READPTR, (uint16_t) 0);
+ memCache.Write(EE_FAULT_LOG + EEFAULT_WRITEPTR, (uint16_t) 0);
+ globalTime = baseTime = millis() / 100;
+ memCache.Write(EE_FAULT_LOG + EEFAULT_RUNTIME, globalTime);
+
+ FAULT tempFault;
+ tempFault.ack = true;
+ tempFault.device = 0xFFFF;
+ tempFault.faultCode = 0xFFFF;
+ tempFault.ongoing = false;
+ tempFault.timeStamp = 0;
+ for (int i = 0; i < CFG_FAULT_HISTORY_SIZE; i++) {
+ faultList[i] = tempFault;
+ }
+ saveToEEPROM();
+ }
+}
+
+void FaultHandler::saveToEEPROM()
+{
+ memCache.Write(EE_FAULT_LOG + EEFAULT_READPTR, faultReadPointer);
+ memCache.Write(EE_FAULT_LOG + EEFAULT_WRITEPTR, faultWritePointer);
+ memCache.Write(EE_FAULT_LOG + EEFAULT_RUNTIME, globalTime);
+ for (int i = 0; i < CFG_FAULT_HISTORY_SIZE; i++) {
+ memCache.Write(EE_FAULT_LOG + EEFAULT_FAULTS_START + sizeof(FAULT) * i, &faultList[i], sizeof(FAULT));
+ }
+}
+
+void FaultHandler::writeFaultToEEPROM(int faultnum)
+{
+ if (faultnum > 0 && faultnum < CFG_FAULT_HISTORY_SIZE) {
+ memCache.Write(EE_FAULT_LOG + EEFAULT_FAULTS_START + sizeof(FAULT) * faultnum, &faultList[faultnum], sizeof(FAULT));
+ }
+}
+
+bool FaultHandler::getNextFault(FAULT *fault)
+{
+ uint16_t j;
+ for (int i = 0; i < CFG_FAULT_HISTORY_SIZE; i++) {
+ j = (faultReadPointer + i + 1) % CFG_FAULT_HISTORY_SIZE;
+ if (faultList[j].ack == false) {
+ fault = &faultList[j];
+ faultReadPointer = j;
+ return true;
+ }
+ }
+ return false;
+}
+
+bool FaultHandler::getFault(uint16_t fault, FAULT *outFault)
+{
+ if (fault > 0 && fault < CFG_FAULT_HISTORY_SIZE) {
+ outFault = &faultList[fault];
+ return true;
+ }
+ return false;
+}
+
+void FaultHandler::setFaultACK(uint16_t fault)
+{
+ if (fault > 0 && fault < CFG_FAULT_HISTORY_SIZE) {
+ faultList[fault].ack = 1;
+ writeFaultToEEPROM(fault);
+ }
+}
+
+void FaultHandler::setFaultOngoing(uint16_t fault, bool ongoing)
+{
+ if (fault > 0 && fault < CFG_FAULT_HISTORY_SIZE) {
+ faultList[fault].ongoing = ongoing;
+ writeFaultToEEPROM(fault);
+ }
+}
+
+FaultHandler faultHandler;
diff --git a/FaultHandler.h b/FaultHandler.h
index ce1338d..fdb6e85 100644
--- a/FaultHandler.h
+++ b/FaultHandler.h
@@ -38,8 +38,6 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
#include "FaultCodes.h"
#include "MemCache.h"
-extern MemCache *memCache;
-
//structure to use for storing and retrieving faults.
//Stores the info a fault record will contain.
typedef struct {
@@ -54,7 +52,9 @@ typedef struct {
class FaultHandler : public TickObserver {
public:
FaultHandler(); //constructor
- uint16_t raiseFault(uint16_t device, uint16_t code, bool ongoing); //raise a new fault. Returns the fault # where this was stored
+ virtual ~FaultHandler();
+
+ void raiseFault(uint16_t device, uint16_t code, bool ongoing); //raise a new fault. Returns the fault # where this was stored
void cancelOngoingFault(uint16_t device, uint16_t code); //if this fault was registered as ongoing then cancel it (set not ongoing) otherwise do nothing
bool getNextFault(FAULT*); //get the next un-ack'd fault. Will also get first fault if the first call and you forgot to call getFirstFault
bool getFault(uint16_t fault, FAULT*);
@@ -62,8 +62,8 @@ class FaultHandler : public TickObserver {
void handleTick();
void setup();
- uint16_t setFaultACK(uint16_t fault); //acknowledge the fault # - returns fault # if successful (0xFFFF otherwise)
- uint16_t setFaultOngoing(uint16_t fault, bool ongoing); //set value of ongoing flag - returns fault # on success
+ void setFaultACK(uint16_t fault); //acknowledge the fault # - returns fault # if successful (0xFFFF otherwise)
+ void setFaultOngoing(uint16_t fault, bool ongoing); //set value of ongoing flag - returns fault # on success
private:
void loadFromEEPROM();
diff --git a/GEVCU.h b/GEVCU.h
index a2fc152..6fd7448 100644
--- a/GEVCU.h
+++ b/GEVCU.h
@@ -29,6 +29,7 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
#include
#include "config.h"
+#include "Status.h"
#include "Device.h"
#include "Throttle.h"
#include "CanThrottle.h"
@@ -37,34 +38,37 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
#include "PotBrake.h"
#include "BatteryManager.h"
#include "ThinkBatteryManager.h"
+#include "OrionBMS.h"
#include "MotorController.h"
#include "DmocMotorController.h"
-#include "BrusaMotorController.h"
+#include "BrusaDMC5.h"
+#include "BrusaBSC6.h"
+#include "BrusaNLG5.h"
#include "Heartbeat.h"
-#include "sys_io.h"
+#include "SystemIO.h"
#include "CanHandler.h"
#include "MemCache.h"
#include "ThrottleDetector.h"
#include "DeviceManager.h"
#include "SerialConsole.h"
#include "ELM327_Emu.h"
-#include "ichip_2128.h"
#include "Sys_Messages.h"
+#include "PerfTimer.h"
#include "CodaMotorController.h"
#include "FaultHandler.h"
+#include "CanIO.h"
+#include "CanOBD2.h"
+#include "StatusIndicator.h"
+#include "WifiEsp32.h"
+#include "WifiIchip2128.h"
#ifdef __cplusplus
extern "C" {
#endif
void loop();
void setup();
-
#ifdef __cplusplus
} // extern "C"
#endif
-#define SYSTEM_PROTO 1
-#define SYSTEM_DUED 2
-#define SYSTEM_GEVCU3 3
-
#endif /* GEVCU_H_ */
diff --git a/GEVCU.ino b/GEVCU.ino
index ce0db35..1288bbe 100644
--- a/GEVCU.ino
+++ b/GEVCU.ino
@@ -1,14 +1,8 @@
/*
GEVCU.ino
-
+
Created: 1/4/2013 1:34:14 PM
- Author: Collin Kidder
-
- New, new plan: Allow for an arbitrary # of devices that can have both tick and canbus handlers. These devices register themselves
- into the handler framework and specify which sort of device they are. They can have custom tick intervals and custom can filters.
- The system automatically manages when to call the tick handlers and automatically filters canbus and sends frames to the devices.
- There is a facility to send data between devices by targetting a certain type of device. For instance, a motor controller
- can ask for any throttles and then retrieve the current throttle position from them.
+ Author: Michael Neuweiler
Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
@@ -32,292 +26,122 @@ TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE
SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
*/
-
-/*Changelog removed. All changes are logged to GIT */
-
-/*
-Random comments on things that should be coded up soon:
-4. It is a possibility that there should be support for actually controlling the power to some of the devices.
- For instance, power could be controlled to the +12V connection at the DMOC so that it can be power cycled
- in software. But, that uses up an input and people can just cycle the key (though that resets the GEVCU too)
-5. Some people (like me, Collin) have a terrible habit of mixing several coding styles. It would be beneficial to
- continue to harmonize the source code - Perhaps use a tool to do this.
-6. It should be possible to limit speed and/or torque in reverse so someone doesn't kill themselves or someone else
- while gunning it in reverse - The configuration variable is there and settable now. Just need to integrate it.
-7. The DMOC code duplicates a bunch of functionality that the base class also used to implement. We've got to figure
- out where the overlaps are and fix it up so that as much as possible is done generically at the base MotorController
- class and not directly in the Dmoc class.
-*/
#include "GEVCU.h"
// The following includes are required in the .ino file by the Arduino IDE in order to properly
// identify the required libraries for the build.
-#include
#include
#include
#include
-//RTC_clock rtc_clock(XTAL); //init RTC with the external 32k crystal as a reference
-
//Evil, global variables
-CanHandler *canHandlerEV;
-CanHandler *canHandlerCar;
-TickHandler *tickHandler;
-PrefHandler *sysPrefs;
-MemCache *memCache;
-Heartbeat *heartbeat;
-SerialConsole *serialConsole;
Device *wifiDevice;
Device *btDevice;
+PerfTimer *mainLoopTimer;
-byte i = 0;
-
-
-void sendWiReach(char* message)
+void createDevices()
{
- Serial2.println(message);
- delay(700);
- while (Serial2.available()) {SerialUSB.write(Serial2.read());}
+ deviceManager.addDevice(new Heartbeat());
+ deviceManager.addDevice(new PotThrottle());
+ deviceManager.addDevice(new CanThrottle());
+ deviceManager.addDevice(new PotBrake());
+ deviceManager.addDevice(new CanBrake());
+ deviceManager.addDevice(new DmocMotorController());
+ deviceManager.addDevice(new CodaMotorController());
+ deviceManager.addDevice(new BrusaDMC5());
+ deviceManager.addDevice(new BrusaBSC6());
+ deviceManager.addDevice(new BrusaNLG5());
+ deviceManager.addDevice(new ThinkBatteryManager());
+ deviceManager.addDevice(new OrionBMS());
+// deviceManager.addDevice(new ELM327Emu());
+ deviceManager.addDevice(new WifiIchip2128());
+ deviceManager.addDevice(new WifiEsp32());
+ deviceManager.addDevice(new CanIO());
+ deviceManager.addDevice(new CanOBD2());
+ deviceManager.addDevice(new StatusIndicator());
}
-void initWiReach()
-{
-SerialUSB.begin(115200); // use SerialUSB only as the programming port doesn't work
-Serial2.begin(115200); // use Serial3 for GEVCU2, use Serial2 for GEVCU3+4
-
-sendWiReach("AT+iFD");//Host connection set to serial port
-delay(5000);
-sendWiReach("AT+iHIF=1");//Host connection set to serial port
-sendWiReach("AT+iBDRF=9");//Automatic baud rate on host serial port
-sendWiReach("AT+iRPG=secret"); //Password for iChip wbsite
-sendWiReach("AT+iWPWD=secret");//Password for our website
-sendWiReach("AT+iWST0=0");//Connection security wap/wep/wap2 to no security
-sendWiReach("AT+iWLCH=4"); //Wireless channel
-sendWiReach("AT+iWLSI=GEVCU");//SSID
-sendWiReach("AT+iWSEC=1");//IF security is used, set for WPA2-AES
-sendWiReach("AT+iSTAP=1");//Act as AP
-sendWiReach("AT+iDIP=192.168.3.10");//default ip - must be 10.x.x.x
-sendWiReach("AT+iDPSZ=8");//DHCP pool size
-sendWiReach("AT+iAWS=1");//Website on
-sendWiReach("AT+iDOWN");//Powercycle reset
-delay(5000);
-SerialUSB.println("WiReach Wireless Module Initialized....");
+void delayStart(uint8_t seconds) {
+ for (int i = seconds; i > 0; i--) {
+ SerialUSB.println(i);
+ delay(1000);
+ }
}
-
-
-
-//initializes all the system EEPROM values. Chances are this should be broken out a bit but
-//there is only one checksum check for all of them so it's simple to do it all here.
-
-void initSysEEPROM() {
- //three temporary storage places to make saving to EEPROM easy
- uint8_t eight;
- uint16_t sixteen;
- uint32_t thirtytwo;
-
- eight = 4; //GEVCU4 or GEVCU5 boards
- sysPrefs->write(EESYS_SYSTEM_TYPE, eight);
-
- sixteen = 1024; //no gain
- sysPrefs->write(EESYS_ADC0_GAIN, sixteen);
- sysPrefs->write(EESYS_ADC1_GAIN, sixteen);
- sysPrefs->write(EESYS_ADC2_GAIN, sixteen);
- sysPrefs->write(EESYS_ADC3_GAIN, sixteen);
-
- sixteen = 0; //no offset
- sysPrefs->write(EESYS_ADC0_OFFSET, sixteen);
- sysPrefs->write(EESYS_ADC1_OFFSET, sixteen);
- sysPrefs->write(EESYS_ADC2_OFFSET, sixteen);
- sysPrefs->write(EESYS_ADC3_OFFSET, sixteen);
-
- sixteen = 500; //multiplied by 1000 so 500k baud
- sysPrefs->write(EESYS_CAN0_BAUD, sixteen);
- sysPrefs->write(EESYS_CAN1_BAUD, sixteen);
-
- sixteen = 11520; //multiplied by 10
- sysPrefs->write(EESYS_SERUSB_BAUD, sixteen);
-
- sixteen = 100; //multiplied by 1000
- sysPrefs->write(EESYS_TWI_BAUD, sixteen);
-
- sixteen = 100; //number of ticks per second
- sysPrefs->write(EESYS_TICK_RATE, sixteen);
-
- thirtytwo = 0;
- sysPrefs->write(EESYS_RTC_TIME, thirtytwo);
- sysPrefs->write(EESYS_RTC_DATE, thirtytwo);
-
- eight = 5; //how many RX mailboxes
- sysPrefs->write(EESYS_CAN_RX_COUNT, eight);
-
- thirtytwo = 0x7f0; //standard frame, ignore bottom 4 bits
- sysPrefs->write(EESYS_CAN_MASK0, thirtytwo);
- sysPrefs->write(EESYS_CAN_MASK1, thirtytwo);
- sysPrefs->write(EESYS_CAN_MASK2, thirtytwo);
- sysPrefs->write(EESYS_CAN_MASK3, thirtytwo);
- sysPrefs->write(EESYS_CAN_MASK4, thirtytwo);
-
- thirtytwo = 0x230;
- sysPrefs->write(EESYS_CAN_FILTER0, thirtytwo);
- sysPrefs->write(EESYS_CAN_FILTER1, thirtytwo);
- sysPrefs->write(EESYS_CAN_FILTER2, thirtytwo);
-
- thirtytwo = 0x650;
- sysPrefs->write(EESYS_CAN_FILTER3, thirtytwo);
- sysPrefs->write(EESYS_CAN_FILTER4, thirtytwo);
-
- thirtytwo = 0; //ok, not technically 32 bytes but the four zeros still shows it is unused.
- sysPrefs->write(EESYS_WIFI0_SSID, thirtytwo);
- sysPrefs->write(EESYS_WIFI1_SSID, thirtytwo);
- sysPrefs->write(EESYS_WIFI2_SSID, thirtytwo);
- sysPrefs->write(EESYS_WIFIX_SSID, thirtytwo);
-
- eight = 0; //no channel, DHCP off, B mode
- sysPrefs->write(EESYS_WIFI0_CHAN, eight);
- sysPrefs->write(EESYS_WIFI0_DHCP, eight);
- sysPrefs->write(EESYS_WIFI0_MODE, eight);
-
- sysPrefs->write(EESYS_WIFI1_CHAN, eight);
- sysPrefs->write(EESYS_WIFI1_DHCP, eight);
- sysPrefs->write(EESYS_WIFI1_MODE, eight);
-
- sysPrefs->write(EESYS_WIFI2_CHAN, eight);
- sysPrefs->write(EESYS_WIFI2_DHCP, eight);
- sysPrefs->write(EESYS_WIFI2_MODE, eight);
-
- sysPrefs->write(EESYS_WIFIX_CHAN, eight);
- sysPrefs->write(EESYS_WIFIX_DHCP, eight);
- sysPrefs->write(EESYS_WIFIX_MODE, eight);
-
- thirtytwo = 0;
- sysPrefs->write(EESYS_WIFI0_IPADDR, thirtytwo);
- sysPrefs->write(EESYS_WIFI1_IPADDR, thirtytwo);
- sysPrefs->write(EESYS_WIFI2_IPADDR, thirtytwo);
- sysPrefs->write(EESYS_WIFIX_IPADDR, thirtytwo);
-
- sysPrefs->write(EESYS_WIFI0_KEY, thirtytwo);
- sysPrefs->write(EESYS_WIFI1_KEY, thirtytwo);
- sysPrefs->write(EESYS_WIFI2_KEY, thirtytwo);
- sysPrefs->write(EESYS_WIFIX_KEY, thirtytwo);
-
- eight = 1;
- sysPrefs->write(EESYS_LOG_LEVEL, eight);
-
- sysPrefs->saveChecksum();
-}
-
-void createObjects() {
- PotThrottle *paccelerator = new PotThrottle();
- CanThrottle *caccelerator = new CanThrottle();
- PotBrake *pbrake = new PotBrake();
- CanBrake *cbrake = new CanBrake();
- DmocMotorController *dmotorController = new DmocMotorController();
- CodaMotorController *cmotorController = new CodaMotorController();
- BrusaMotorController *bmotorController = new BrusaMotorController();
- ThinkBatteryManager *BMS = new ThinkBatteryManager();
- ELM327Emu *emu = new ELM327Emu();
- ICHIPWIFI *iChip = new ICHIPWIFI();
+void setup()
+{
+ SerialUSB.begin(CFG_SERIAL_SPEED);
+// delayStart(3);
+ SerialUSB.println(CFG_VERSION);
+
+ // resets CPU when power drops below 2.8V --> give the EEPROM enough time to finish an ongoing write at power-down
+ SUPC->SUPC_SMMR = 0xA | (1<<8) | (1<<12);
+
+ memCache.setup();
+ faultHandler.setup();
+ systemIO.setup();
+ canHandlerEv.setup();
+ canHandlerCar.setup();
+
+ createDevices();
+ /*
+ * We defer setting up the devices until here. This allows all objects to be instantiated
+ * before any of them set up. That in turn allows the devices to inspect what else is
+ * out there as they initialize. For instance, a motor controller could see if a BMS
+ * exists and supports a function that the motor controller wants to access.
+ */
+ status.setSystemState(Status::init);
+
+ // if no dcdc converter is enabled, set status to true to keep high power devices running
+ if (deviceManager.getDcDcConverter() == NULL) {
+ status.dcdcRunning = true;
+ }
+
+ serialConsole.printMenu();
+
+ wifiDevice = deviceManager.getDeviceByType(DEVICE_WIFI);
+ btDevice = deviceManager.getDeviceByID(ELM327EMU);
+
+ status.setSystemState(Status::preCharge);
+
+#ifdef CFG_EFFICIENCY_CALCS
+ mainLoopTimer = new PerfTimer();
+#endif
}
-void initializeDevices() {
- DeviceManager *deviceManager = DeviceManager::getInstance();
-
- //heartbeat is always enabled now
- heartbeat = new Heartbeat();
- Logger::info("add: Heartbeat (id: %X, %X)", HEARTBEAT, heartbeat);
- heartbeat->setup();
-
- //fault handler is always enabled too - its also statically allocated so no using -> here
- //This is initialized before the other devices so that they can go ahead and use it if they fault upon start up
- faultHandler.setup();
-
- /*
- We used to instantiate all the objects here along with other code. To simplify things this is done somewhat
- automatically now. Just instantiate your new device object in createObjects above. This takes care of the details
- so long as you follow the template of how other devices were coded.
- */
- createObjects();
+void loop()
+{
+#ifdef CFG_EFFICIENCY_CALCS
+ static int counts = 0;
+ counts++;
+ if (counts > 200000) {
+ counts = 0;
+ mainLoopTimer->printValues();
+ }
- /*
- * We defer setting up the devices until here. This allows all objects to be instantiated
- * before any of them set up. That in turn allows the devices to inspect what else is
- * out there as they initialize. For instance, a motor controller could see if a BMS
- * exists and supports a function that the motor controller wants to access.
- */
- deviceManager->sendMessage(DEVICE_ANY, INVALID, MSG_STARTUP, NULL);
+ mainLoopTimer->start();
+#endif
-}
+ tickHandler.process();
+ canHandlerEv.process();
+ canHandlerCar.process();
-void setup() {
- //delay(5000); //This delay lets you see startup. But it breaks DMOC645 really badly. You have to have comm way before 5 seconds.
-
- //initWiReach();
- pinMode(BLINK_LED, OUTPUT);
- digitalWrite(BLINK_LED, LOW);
- SerialUSB.begin(CFG_SERIAL_SPEED);
- SerialUSB.println(CFG_VERSION);
- SerialUSB.print("Build number: ");
- SerialUSB.println(CFG_BUILD_NUM);
- Wire.begin();
- Logger::info("TWI init ok");
- memCache = new MemCache();
- Logger::info("add MemCache (id: %X, %X)", MEMCACHE, memCache);
- memCache->setup();
- sysPrefs = new PrefHandler(SYSTEM);
- if (!sysPrefs->checksumValid())
- {
- Logger::info("Initializing EEPROM");
- initSysEEPROM();
- initWiReach();
- }
- else {Logger::info("Using existing EEPROM values");}//checksum is good, read in the values stored in EEPROM
+ serialConsole.loop();
- uint8_t loglevel;
- sysPrefs->read(EESYS_LOG_LEVEL, &loglevel);
- Logger::setLoglevel((Logger::LogLevel)loglevel);
- Logger::setLoglevel((Logger::LogLevel)1);
- sys_early_setup();
- tickHandler = TickHandler::getInstance();
- canHandlerEV = CanHandler::getInstanceEV();
- canHandlerCar = CanHandler::getInstanceCar();
- canHandlerEV->initialize();
- canHandlerCar->initialize();
- setup_sys_io(); //get calibration data for system IO
- Logger::info("SYSIO init ok");
+ //TODO: this is dumb... shouldn't have to manually do this. Devices should be able to register loop functions
+ if (wifiDevice != NULL) {
+ ((Wifi*) wifiDevice)->process();
+ }
- initializeDevices();
- serialConsole = new SerialConsole(memCache, heartbeat);
- serialConsole->printMenu();
- wifiDevice = DeviceManager::getInstance()->getDeviceByID(ICHIP2128);
- btDevice = DeviceManager::getInstance()->getDeviceByID(ELM327EMU);
- DeviceManager::getInstance()->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_CONFIG_CHANGE, NULL); //Load configuration variables into WiFi Web Configuration screen
- Logger::info("System Ready");
-}
+// if (btDevice != NULL) {
+// ((ELM327Emu*) btDevice)->loop();
+// }
-void loop() {
+ //this should still be here. It checks for a flag set during an interrupt
+ systemIO.ADCPoll();
-#ifdef CFG_TIMER_USE_QUEUING
- tickHandler->process();
+#ifdef CFG_EFFICIENCY_CALCS
+ mainLoopTimer->stop();
#endif
-
- // check if incoming frames are available in the can buffer and process them
- canHandlerEV->process();
- canHandlerCar->process();
-
- serialConsole->loop();
- //TODO: this is dumb... shouldn't have to manually do this. Devices should be able to register loop functions
- if ( wifiDevice != NULL ) {
- ((ICHIPWIFI*)wifiDevice)->loop();
- }
-
- //if (btDevice != NULL) {
- // ((ELM327Emu*)btDevice)->loop();
- //}
-
- //this should still be here. It checks for a flag set during an interrupt
- sys_io_adc_poll();
}
-
-
diff --git a/GEVCU.kdev4 b/GEVCU.kdev4
deleted file mode 100644
index dbaac6f..0000000
--- a/GEVCU.kdev4
+++ /dev/null
@@ -1,4 +0,0 @@
-[Project]
-Name=GEVCU
-Manager=KDevCMakeManager
-VersionControl=kdevgit
diff --git a/GEVCU.sln b/GEVCU.sln
deleted file mode 100644
index a1cb715..0000000
--- a/GEVCU.sln
+++ /dev/null
@@ -1,20 +0,0 @@
-
-Microsoft Visual Studio Solution File, Format Version 12.00
-# Visual Studio 2012
-Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "GEVCU", "GEVCU.vcxproj", "{6BFAB833-3C53-4597-9B31-C33D5EA78172}"
-EndProject
-Global
- GlobalSection(SolutionConfigurationPlatforms) = preSolution
- Debug|Win32 = Debug|Win32
- Release|Win32 = Release|Win32
- EndGlobalSection
- GlobalSection(ProjectConfigurationPlatforms) = postSolution
- {6BFAB833-3C53-4597-9B31-C33D5EA78172}.Debug|Win32.ActiveCfg = Debug|Win32
- {6BFAB833-3C53-4597-9B31-C33D5EA78172}.Debug|Win32.Build.0 = Debug|Win32
- {6BFAB833-3C53-4597-9B31-C33D5EA78172}.Release|Win32.ActiveCfg = Release|Win32
- {6BFAB833-3C53-4597-9B31-C33D5EA78172}.Release|Win32.Build.0 = Release|Win32
- EndGlobalSection
- GlobalSection(SolutionProperties) = preSolution
- HideSolutionNode = FALSE
- EndGlobalSection
-EndGlobal
diff --git a/GEVCU.vcxproj b/GEVCU.vcxproj
deleted file mode 100644
index 2918951..0000000
--- a/GEVCU.vcxproj
+++ /dev/null
@@ -1,175 +0,0 @@
-
-
-
-
- Debug
- Win32
-
-
- Release
- Win32
-
-
-
- {6BFAB833-3C53-4597-9B31-C33D5EA78172}
- Win32Proj
-
-
-
- Application
- true
- v110
-
-
- Application
- false
- v110
-
-
-
-
-
-
-
-
-
-
-
-
- true
-
-
- true
-
-
-
- __SAM3X8E__;USB_VID=0x2341;USB_PID=0x003e;USBCON;USB_MANUFACTURER="Unknown";USB_PRODUCT="Arduino Due";_VMDEBUG=1;ARDUINO=154;ARDUINO_MAIN;printf=iprintf;__SAM__;__sam__;F_CPU=84000000L;__cplusplus;%(PreprocessorDefinitions)
- MultiThreadedDebugDLL
- Level3
- ProgramDatabase
- Disabled
- true
- c:\arduino-1.5.4\hardware\arduino\sam\cores\arduino;c:\arduino-1.5.4\hardware\arduino\sam\variants\arduino_due_x;C:\Users\collin\Documents\Arduino\libraries\due_rtc;C:\Users\collin\Documents\Arduino\libraries\due_rtc\utility;C:\Users\collin\Documents\Arduino\libraries\due_can;C:\Users\collin\Documents\Arduino\libraries\due_can\utility;C:\Users\collin\Documents\Arduino\libraries\due_wire;C:\Users\collin\Documents\Arduino\libraries\due_wire\utility;C:\Users\collin\Documents\Arduino\libraries\DueTimer;C:\Users\collin\Documents\Arduino\libraries\DueTimer\utility;c:\arduino-1.5.4\libraries;c:\arduino-1.5.4\hardware\arduino\sam\libraries;C:\Program Files (x86)\Visual Micro\Visual Micro for Arduino\Micro Platforms\default\debuggers;C:\Users\collin\Documents\Arduino\libraries;c:\arduino-1.5.4\hardware\arduino\sam\system\CMSIS\Device\ATMEL\;c:\arduino-1.5.4\hardware\arduino\sam\system\libsam;c:\arduino-1.5.4\hardware\arduino\sam\system\libsam\include;c:\arduino-1.5.4\hardware\arduino\sam\system\CMSIS\CMSIS\Include\;c:\arduino-1.5.4\hardware\arduino\sam\system\CMSIS\CMSIS\Include\;c:\arduino-1.5.4\hardware\arduino\sam\system\CMSIS\Device\ATMEL\;c:\arduino-1.5.4\hardware\arduino\sam\system\libsam;c:\arduino-1.5.4\hardware\arduino\sam\system\libsam\include;c:\arduino-1.5.4/hardware/tools/g++_arm_none_eabi\arm-none-eabi\include;c:\arduino-1.5.4/hardware/tools/g++_arm_none_eabi\arm_none_eabi\include\;c:\arduino-1.5.4/hardware/tools/g++_arm_none_eabi\lib\gcc\arm-none-eabi\4.4.1\include;c:\arduino-1.5.4/hardware/tools/g++_arm_none_eabi\lib\gcc\arm-none-eabi\4.4.1\include\;%(AdditionalIncludeDirectories)
- C:\Users\collin\Desktop\GEVCU\Visual Micro\.GEVCU.vsarduino.h;%(ForcedIncludeFiles)
- true
-
-
- MachineX86
- true
- Console
-
-
- true
-
-
-
-
- WIN32;NDEBUG;_CONSOLE;%(PreprocessorDefinitions)
- MultiThreadedDLL
- Level3
- ProgramDatabase
-
-
- MachineX86
- true
- Console
- true
- true
-
-
-
-
-
- CppCode
-
-
-
-
-
-
-
-
- CppCode
-
-
-
-
- CppCode
-
-
-
-
-
-
-
-
-
- CppCode
-
-
-
-
-
-
-
- CppCode
-
-
-
-
- CppCode
-
-
-
-
-
-
- CppCode
-
-
-
-
-
-
- CppCode
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
\ No newline at end of file
diff --git a/GEVCU.vcxproj.filters b/GEVCU.vcxproj.filters
deleted file mode 100644
index 7e5980b..0000000
--- a/GEVCU.vcxproj.filters
+++ /dev/null
@@ -1,216 +0,0 @@
-
-
-
-
- {4FC737F1-C7A5-4376-A066-2A32D752A2FF}
- cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx
-
-
- {93995380-89BD-4b04-88EB-625FBE52EBFB}
- h;hpp;hxx;hm;inl;inc;xsd
-
-
- {67DA6AB6-F800-4c08-8B7A-83BB121AAD01}
- rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx;tiff;tif;png;wav
-
-
-
-
- Header Files
-
-
- Header Files
-
-
- Header Files
-
-
- Header Files
-
-
- Header Files
-
-
- Header Files
-
-
- Header Files
-
-
- Header Files
-
-
- Header Files
-
-
- Header Files
-
-
- Header Files
-
-
- Header Files
-
-
- Header Files
-
-
- Header Files
-
-
- Header Files
-
-
- Header Files
-
-
- Header Files
-
-
- Header Files
-
-
- Header Files
-
-
- Header Files
-
-
- Header Files
-
-
- Header Files
-
-
- Header Files
-
-
- Header Files
-
-
- Header Files
-
-
- Header Files
-
-
- Header Files
-
-
- Header Files
-
-
- Header Files
-
-
- Header Files
-
-
- Header Files
-
-
- Header Files
-
-
- Header Files
-
-
- Header Files
-
-
- Header Files
-
-
- Header Files
-
-
-
-
-
-
-
- Source Files
-
-
- Source Files
-
-
- Source Files
-
-
- Source Files
-
-
- Source Files
-
-
- Source Files
-
-
- Source Files
-
-
- Source Files
-
-
- Source Files
-
-
- Source Files
-
-
- Source Files
-
-
- Source Files
-
-
- Source Files
-
-
- Source Files
-
-
- Source Files
-
-
- Source Files
-
-
- Source Files
-
-
- Source Files
-
-
- Source Files
-
-
- Source Files
-
-
- Source Files
-
-
- Source Files
-
-
- Source Files
-
-
- Source Files
-
-
- Source Files
-
-
- Source Files
-
-
- Source Files
-
-
- Source Files
-
-
-
\ No newline at end of file
diff --git a/Heartbeat.cpp b/Heartbeat.cpp
index dafd0b4..5017fdd 100644
--- a/Heartbeat.cpp
+++ b/Heartbeat.cpp
@@ -26,66 +26,104 @@
#include "Heartbeat.h"
-Heartbeat::Heartbeat() {
- led = false;
- throttleDebug = false;
+Heartbeat::Heartbeat() : Device()
+{
+ prefsHandler = new PrefHandler(HEARTBEAT);
+ led = false;
+ throttleDebug = false;
+ dotCount = 0;
+ lastTickTime = 0;
+ commonName = "Heartbeat";
}
-void Heartbeat::setup() {
- TickHandler::getInstance()->detach(this);
+void Heartbeat::setup()
+{
+ Device::setup();
- TickHandler::getInstance()->attach(this, CFG_TICK_INTERVAL_HEARTBEAT);
+ pinMode(CFG_IO_BLINK_LED, OUTPUT);
+ digitalWrite(CFG_IO_BLINK_LED, LOW);
+ ready = true;
+ running = true;
+
+ tickHandler.attach(this, CFG_TICK_INTERVAL_HEARTBEAT);
}
-void Heartbeat::setThrottleDebug(bool debug) {
- throttleDebug = debug;
+void Heartbeat::setThrottleDebug(bool debug)
+{
+ throttleDebug = debug;
}
-bool Heartbeat::getThrottleDebug() {
- return throttleDebug;
+bool Heartbeat::getThrottleDebug()
+{
+ return throttleDebug;
}
-void Heartbeat::handleTick() {
- // Print a dot if no other output has been made since the last tick
- if (Logger::getLastLogTime() < lastTickTime) {
- SerialUSB.print('.');
- if ((++dotCount % 80) == 0) {
- SerialUSB.println();
- }
- }
- lastTickTime = millis();
-
- if (led) {
- digitalWrite(BLINK_LED, HIGH);
- } else {
- digitalWrite(BLINK_LED, LOW);
- }
- led = !led;
-
- if (throttleDebug) {
- MotorController *motorController = DeviceManager::getInstance()->getMotorController();
- Throttle *accelerator = DeviceManager::getInstance()->getAccelerator();
- Throttle *brake = DeviceManager::getInstance()->getBrake();
-
- Logger::console("");
- if (motorController) {
- Logger::console("Motor Controller Status: isRunning: %T isFaulted: %T", motorController->isRunning(), motorController->isFaulted());
- }
-
- Logger::console("AIN0: %d, AIN1: %d, AIN2: %d, AIN3: %d", getAnalog(0), getAnalog(1), getAnalog(2), getAnalog(3));
- Logger::console("DIN0: %d, DIN1: %d, DIN2: %d, DIN3: %d", getDigital(0), getDigital(1), getDigital(2), getDigital(3));
- Logger::console("DOUT0: %d, DOUT1: %d, DOUT2: %d, DOUT3: %d,DOUT4: %d, DOUT5: %d, DOUT6: %d, DOUT7: %d", getOutput(0), getOutput(1), getOutput(2), getOutput(3),getOutput(4), getOutput(5), getOutput(6), getOutput(7));
-
- if (accelerator) {
- Logger::console("Throttle Status: isFaulted: %T level: %i", accelerator->isFaulted(), accelerator->getLevel());
- RawSignalData *rawSignal = accelerator->acquireRawSignal();
- Logger::console("Throttle rawSignal1: %d, rawSignal2: %d", rawSignal->input1, rawSignal->input2);
- }
- if (brake) {
- Logger::console("Brake Output: %i", brake->getLevel());
- RawSignalData *rawSignal = brake->acquireRawSignal();
- Logger::console("Brake rawSignal1: %d", rawSignal->input1);
- }
- }
+void Heartbeat::handleTick()
+{
+ SerialUSB.print('.');
+
+ if ((++dotCount % 80) == 0) {
+ SerialUSB.println();
+ }
+
+ lastTickTime = millis();
+
+ if (led) {
+ digitalWrite(CFG_IO_BLINK_LED, HIGH);
+ } else {
+ digitalWrite(CFG_IO_BLINK_LED, LOW);
+ }
+
+ led = !led;
+
+ if (throttleDebug) {
+ Throttle *accelerator = deviceManager.getAccelerator();
+ Throttle *brake = deviceManager.getBrake();
+
+ logger.console("");
+
+ logger.console("System State: %s", status.systemStateToStr(status.getSystemState()).c_str());
+ systemIO.printIOStatus();
+
+ if (accelerator) {
+ logger.console("Throttle Status: isFaulted: %d level: %i", accelerator->isFaulted(), accelerator->getLevel());
+ RawSignalData *rawSignal = accelerator->acquireRawSignal();
+ logger.console("Throttle rawSignal1: %d, rawSignal2: %d", rawSignal->input1, rawSignal->input2);
+ }
+
+ if (brake) {
+ logger.console("Brake Output: %i", brake->getLevel());
+ RawSignalData *rawSignal = brake->acquireRawSignal();
+ logger.console("Brake rawSignal1: %d", rawSignal->input1);
+ }
+ }
}
+DeviceType Heartbeat::getType()
+{
+ return DEVICE_MISC;
+}
+
+DeviceId Heartbeat::getId()
+{
+ return HEARTBEAT;
+}
+
+void Heartbeat::loadConfiguration()
+{
+// HeartbeatConfiguration *config = (HeartbeatConfiguration *) getConfiguration();
+
+ if (prefsHandler->checksumValid()) { //checksum is good, read in the values stored in EEPROM
+// prefsHandler->read(EESYS_, &config->);
+ } else {
+ saveConfiguration();
+ }
+}
+
+void Heartbeat::saveConfiguration()
+{
+// HeartbeatConfiguration *config = (HeartbeatConfiguration *) getConfiguration();
+
+// prefsHandler->write(EESYS_, config->);
+ prefsHandler->saveChecksum();
+}
diff --git a/Heartbeat.h b/Heartbeat.h
index 5439735..a7b3c12 100644
--- a/Heartbeat.h
+++ b/Heartbeat.h
@@ -30,23 +30,30 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
#include "config.h"
#include "TickHandler.h"
#include "DeviceManager.h"
-#include "sys_io.h"
+#include "SystemIO.h"
+#include "Status.h"
-class Heartbeat: public TickObserver {
+class Heartbeat: public Device
+{
public:
- Heartbeat();
- void setup();
- void handleTick();
- void setThrottleDebug(bool debug);
- bool getThrottleDebug();
+ Heartbeat();
+ void setup();
+ void handleTick();
+ DeviceType getType();
+ DeviceId getId();
+ void setThrottleDebug(bool debug);
+ bool getThrottleDebug();
+
+ void loadConfiguration();
+ void saveConfiguration();
protected:
private:
- bool led;
- bool throttleDebug;
- int dotCount;
- uint32_t lastTickTime;
+ bool led;
+ bool throttleDebug;
+ int dotCount;
+ uint32_t lastTickTime;
};
#endif /* HEARTBEAT_H_ */
diff --git a/Logger.cpp b/Logger.cpp
index 84a6b31..a1c09ea 100644
--- a/Logger.cpp
+++ b/Logger.cpp
@@ -25,145 +25,210 @@
*/
#include "Logger.h"
+#include "Device.h"
+#include "DeviceManager.h"
-Logger::LogLevel Logger::logLevel = Logger::Info;
-uint32_t Logger::lastLogTime = 0;
+Logger logger;
+
+Logger::Logger() {
+ logLevel = CFG_DEFAULT_LOGLEVEL;
+ debugging = false;
+ deviceLoglevel = new Logger::LogLevel[deviceIdsSize];
+ lastMsgRepeated = 0;
+ repeatStart = 0;
+ historyPtr = 0;
+}
/*
* Output a debug message with a variable amount of parameters.
* printf() style, see Logger::log()
*
*/
-void Logger::debug(char *message, ...) {
- if (logLevel > Debug)
- return;
- va_list args;
- va_start(args, message);
- Logger::log((DeviceId) NULL, Debug, message, args);
- va_end(args);
+void Logger::debug(String message, ...)
+{
+ if (logLevel > Debug) {
+ return;
+ }
+
+ va_list args;
+ va_start(args, message);
+ log("", Debug, message, args);
+ va_end(args);
}
/*
* Output a debug message with the name of a device appended before the message
* printf() style, see Logger::log()
*/
-void Logger::debug(DeviceId deviceId, char *message, ...) {
- if (logLevel > Debug)
- return;
- va_list args;
- va_start(args, message);
- Logger::log(deviceId, Debug, message, args);
- va_end(args);
+void Logger::debug(Device *device, String message, ...)
+{
+ if (getLogLevel(device) > Debug) {
+ return;
+ }
+
+ va_list args;
+ va_start(args, message);
+ log(device->getCommonName(), Debug, message, args);
+ va_end(args);
}
/*
* Output a info message with a variable amount of parameters
* printf() style, see Logger::log()
*/
-void Logger::info(char *message, ...) {
- if (logLevel > Info)
- return;
- va_list args;
- va_start(args, message);
- Logger::log((DeviceId) NULL, Info, message, args);
- va_end(args);
+void Logger::info(String message, ...)
+{
+ if (logLevel > Info) {
+ return;
+ }
+
+ va_list args;
+ va_start(args, message);
+ log("", Info, message, args);
+ va_end(args);
}
/*
* Output a info message with the name of a device appended before the message
* printf() style, see Logger::log()
*/
-void Logger::info(DeviceId deviceId, char *message, ...) {
- if (logLevel > Info)
- return;
- va_list args;
- va_start(args, message);
- Logger::log(deviceId, Info, message, args);
- va_end(args);
+void Logger::info(Device *device, String message, ...)
+{
+ if (getLogLevel(device) > Info) {
+ return;
+ }
+
+ va_list args;
+ va_start(args, message);
+ Logger::log(device->getCommonName(), Info, message, args);
+ va_end(args);
}
/*
* Output a warning message with a variable amount of parameters
* printf() style, see Logger::log()
*/
-void Logger::warn(char *message, ...) {
- if (logLevel > Warn)
- return;
- va_list args;
- va_start(args, message);
- Logger::log((DeviceId) NULL, Warn, message, args);
- va_end(args);
+void Logger::warn(String message, ...)
+{
+ if (logLevel > Warn) {
+ return;
+ }
+
+ va_list args;
+ va_start(args, message);
+ log("", Warn, message, args);
+ va_end(args);
}
/*
* Output a warning message with the name of a device appended before the message
* printf() style, see Logger::log()
*/
-void Logger::warn(DeviceId deviceId, char *message, ...) {
- if (logLevel > Warn)
- return;
- va_list args;
- va_start(args, message);
- Logger::log(deviceId, Warn, message, args);
- va_end(args);
+void Logger::warn(Device *device, String message, ...)
+{
+ if (getLogLevel(device) > Warn) {
+ return;
+ }
+
+ va_list args;
+ va_start(args, message);
+ log(device->getCommonName(), Warn, message, args);
+ va_end(args);
}
/*
* Output a error message with a variable amount of parameters
* printf() style, see Logger::log()
*/
-void Logger::error(char *message, ...) {
- if (logLevel > Error)
- return;
- va_list args;
- va_start(args, message);
- Logger::log((DeviceId) NULL, Error, message, args);
- va_end(args);
+void Logger::error(String message, ...)
+{
+ if (logLevel > Error) {
+ return;
+ }
+
+ va_list args;
+ va_start(args, message);
+ log("", Error, message, args);
+ va_end(args);
}
/*
* Output a error message with the name of a device appended before the message
* printf() style, see Logger::log()
*/
-void Logger::error(DeviceId deviceId, char *message, ...) {
- if (logLevel > Error)
- return;
- va_list args;
- va_start(args, message);
- Logger::log(deviceId, Error, message, args);
- va_end(args);
+void Logger::error(Device *device, String message, ...)
+{
+ if (getLogLevel(device) > Error) {
+ return;
+ }
+
+ va_list args;
+ va_start(args, message);
+ log(device->getCommonName(), Error, message, args);
+ va_end(args);
}
/*
* Output a comnsole message with a variable amount of parameters
* printf() style, see Logger::logMessage()
*/
-void Logger::console(char *message, ...) {
- va_list args;
- va_start(args, message);
- Logger::logMessage(message, args);
- va_end(args);
+void Logger::console(String message, ...)
+{
+ va_list args;
+ va_start(args, message);
+ vsnprintf(msgBuffer, LOG_BUFFER_SIZE, message.c_str(), args);
+ SerialUSB.println(msgBuffer);
+ va_end(args);
}
/*
* Set the log level. Any output below the specified log level will be omitted.
+ * Also set the debugging flag for faster evaluation in isDebug().
*/
-void Logger::setLoglevel(LogLevel level) {
- logLevel = level;
+void Logger::setLoglevel(LogLevel level)
+{
+ logLevel = level;
+ for (int deviceEntry = 0; deviceEntry < deviceIdsSize; deviceEntry ++) {
+ deviceLoglevel[deviceEntry] = level;
+ }
+ debugging = (level == Debug);
}
+/*
+ * Set the log level for a specific device. If one device has Debugging loglevel set, also set the
+ * debugging flag (for faster evaluation in isDebug()).
+ */
+void Logger::setLoglevel(Device *device, LogLevel level)
+{
+ debugging = false;
+ for (int deviceEntry = 0; deviceEntry < deviceIdsSize; deviceEntry ++) {
+ if (deviceIds[deviceEntry] == device->getId()) {
+ deviceLoglevel[deviceEntry] = level;
+ }
+ if (deviceLoglevel[deviceEntry] == Debug) {
+ debugging = true;
+ }
+ }
+}
/*
* Retrieve the current log level.
*/
-Logger::LogLevel Logger::getLogLevel() {
- return logLevel;
+Logger::LogLevel Logger::getLogLevel()
+{
+ return logLevel;
}
/*
- * Return a timestamp when the last log entry was made.
+ * Retrieve the specific log level of a device
*/
-uint32_t Logger::getLastLogTime() {
- return lastLogTime;
+Logger::LogLevel Logger::getLogLevel(Device *device)
+{
+ for (int deviceEntry = 0; deviceEntry < deviceIdsSize; deviceEntry ++) {
+ if (deviceIds[deviceEntry] == device->getId()) {
+ return deviceLoglevel[deviceEntry];
+ }
+ }
+ return logLevel;
}
/*
@@ -176,197 +241,109 @@ uint32_t Logger::getLastLogTime() {
* Logger::debug("current time: %d", millis());
* }
*/
-boolean Logger::isDebug() {
- return logLevel == Debug;
+boolean Logger::isDebug()
+{
+ return debugging;
}
/*
* Output a log message (called by debug(), info(), warn(), error(), console())
- *
- * Supports printf() like syntax:
- *
- * %% - outputs a '%' character
- * %s - prints the next parameter as string
- * %d - prints the next parameter as decimal
- * %f - prints the next parameter as double float
- * %x - prints the next parameter as hex value
- * %X - prints the next parameter as hex value with '0x' added before
- * %b - prints the next parameter as binary value
- * %B - prints the next parameter as binary value with '0b' added before
- * %l - prints the next parameter as long
- * %c - prints the next parameter as a character
- * %t - prints the next parameter as boolean ('T' or 'F')
- * %T - prints the next parameter as boolean ('true' or 'false')
*/
-void Logger::log(DeviceId deviceId, LogLevel level, char *format, va_list args) {
- lastLogTime = millis();
- SerialUSB.print(lastLogTime);
- SerialUSB.print(" - ");
-
- switch (level) {
- case Debug:
- SerialUSB.print("DEBUG");
- break;
- case Info:
- SerialUSB.print("INFO");
- break;
- case Warn:
- SerialUSB.print("WARNING");
- break;
- case Error:
- SerialUSB.print("ERROR");
- break;
- }
- SerialUSB.print(": ");
-
- if (deviceId)
- printDeviceName(deviceId);
-
- logMessage(format, args);
+void Logger::log(String deviceName, LogLevel level, String format, va_list args)
+{
+ vsnprintf(msgBuffer, LOG_BUFFER_SIZE, format.c_str(), args);
+ LogEntry logEntry = createLogEntry(level, deviceName, String(msgBuffer));
+
+ logToPrinter(SerialUSB, logEntry);
+ logToWifi(logEntry);
}
-/*
- * Output a log message (called by log(), console())
- *
- * Supports printf() like syntax:
- *
- * %% - outputs a '%' character
- * %s - prints the next parameter as string
- * %d - prints the next parameter as decimal
- * %f - prints the next parameter as double float
- * %x - prints the next parameter as hex value
- * %X - prints the next parameter as hex value with '0x' added before
- * %b - prints the next parameter as binary value
- * %B - prints the next parameter as binary value with '0b' added before
- * %l - prints the next parameter as long
- * %c - prints the next parameter as a character
- * %t - prints the next parameter as boolean ('T' or 'F')
- * %T - prints the next parameter as boolean ('true' or 'false')
- */
-void Logger::logMessage(char *format, va_list args) {
- for (; *format != 0; ++format) {
- if (*format == '%') {
- ++format;
- if (*format == '\0')
- break;
- if (*format == '%') {
- SerialUSB.print(*format);
- continue;
- }
- if (*format == 's') {
- register char *s = (char *) va_arg( args, int );
- SerialUSB.print(s);
- continue;
- }
- if (*format == 'd' || *format == 'i') {
- SerialUSB.print(va_arg( args, int ), DEC);
- continue;
- }
- if (*format == 'f') {
- SerialUSB.print(va_arg( args, double ), 2);
- continue;
- }
- if (*format == 'x') {
- SerialUSB.print(va_arg( args, int ), HEX);
- continue;
- }
- if (*format == 'X') {
- SerialUSB.print("0x");
- SerialUSB.print(va_arg( args, int ), HEX);
- continue;
- }
- if (*format == 'b') {
- SerialUSB.print(va_arg( args, int ), BIN);
- continue;
- }
- if (*format == 'B') {
- SerialUSB.print("0b");
- SerialUSB.print(va_arg( args, int ), BIN);
- continue;
- }
- if (*format == 'l') {
- SerialUSB.print(va_arg( args, long ), DEC);
- continue;
- }
-
- if (*format == 'c') {
- SerialUSB.print(va_arg( args, int ));
- continue;
- }
- if (*format == 't') {
- if (va_arg( args, int ) == 1) {
- SerialUSB.print("T");
- } else {
- SerialUSB.print("F");
- }
- continue;
- }
- if (*format == 'T') {
- if (va_arg( args, int ) == 1) {
- SerialUSB.print(Constants::trueStr);
- } else {
- SerialUSB.print(Constants::falseStr);
- }
- continue;
- }
-
- }
- SerialUSB.print(*format);
- }
- SerialUSB.println();
+Logger::LogEntry &Logger::createLogEntry(Logger::LogLevel level, String deviceName, String message)
+{
+ LogEntry &entry = history[historyPtr++];
+
+ if (historyPtr > HISTORY_SIZE - 1) {
+ historyPtr = 0;
+ }
+
+ entry.time = millis();
+ entry.level = level;
+ entry.deviceName = deviceName;
+ entry.message = message;
+
+ return entry;
}
-/*
- * When the deviceId is specified when calling the logger, print the name
- * of the device after the log-level. This makes it easier to identify the
- * source of the logged message.
- * NOTE: Should be kept in synch with the defined devices.
- */
-void Logger::printDeviceName(DeviceId deviceId) {
- switch (deviceId) {
- case DMOC645:
- SerialUSB.print("DMOC645");
- break;
- case BRUSA_DMC5:
- SerialUSB.print("DMC5");
- break;
- case BRUSACHARGE:
- SerialUSB.print("NLG5");
- break;
- case TCCHCHARGE:
- SerialUSB.print("TCCH");
- break;
- case THROTTLE:
- SerialUSB.print("THROTTLE");
- break;
- case POTACCELPEDAL:
- SerialUSB.print("POTACCEL");
- break;
- case POTBRAKEPEDAL:
- SerialUSB.print("POTBRAKE");
- break;
- case CANACCELPEDAL:
- SerialUSB.print("CANACCEL");
- break;
- case CANBRAKEPEDAL:
- SerialUSB.print("CANBRAKE");
- break;
- case ICHIP2128:
- SerialUSB.print("ICHIP");
- break;
- case THINKBMS:
- SerialUSB.print("THINKBMS");
- break;
- case SYSTEM:
- SerialUSB.print("SYSTEM");
- break;
- case HEARTBEAT:
- SerialUSB.print("HEARTBEAT");
- break;
- case MEMCACHE:
- SerialUSB.print("MEMCACHE");
- break;
- }
- SerialUSB.print(" - ");
+String Logger::logLevelToString(Logger::LogLevel level)
+{
+ switch (level) {
+ case Info:
+ return "INFO";
+ case Warn:
+ return "WARNING";
+ case Error:
+ return "ERROR";
+ case Debug:
+ return "DEBUG";
+ }
+ return "";
+}
+
+void Logger::logToPrinter(Print &printer, LogEntry &logEntry)
+{
+ printer.print(logEntry.time);
+ printer.print(" - ");
+ printer.print(logLevelToString(logEntry.level));
+ printer.print(": ");
+ if (logEntry.deviceName.length() > 0) {
+ printer.print(logEntry.deviceName);
+ printer.print(" - ");
+ }
+ printer.println(logEntry.message);
+}
+
+void Logger::logToWifi(LogEntry &logEntry)
+{
+ if (logEntry.level > Debug) {
+ LogEntry lastEntry = history[(historyPtr == 0 ? HISTORY_SIZE - 1 : historyPtr - 1)];
+ if (logEntry.message.equals(lastEntry.message) && (repeatStart == 0 || (repeatStart + CFG_LOG_REPEAT_MSG_TIME) > millis())) {
+ if (lastMsgRepeated == 0) {
+ repeatStart = millis();
+ }
+ lastMsgRepeated++;
+ } else {
+ if (lastMsgRepeated > 1) {
+ String info = String("Last message repeated ");
+ info.concat(lastMsgRepeated);
+ info.concat(" times");
+ String params[] = { "INFO", "", info };
+ deviceManager.sendMessage(DEVICE_WIFI, INVALID, MSG_LOG, params);
+ lastMsgRepeated = 0;
+ repeatStart = 0;
+ }
+
+ String params[] = { logLevelToString(logEntry.level), logEntry.deviceName, logEntry.message };
+ deviceManager.sendMessage(DEVICE_WIFI, INVALID, MSG_LOG, params);
+ }
+ }
+}
+
+void Logger::printHistory(Print &printer) {
+ printer.println("LOG START");
+ for (uint16_t i = historyPtr; i < HISTORY_SIZE - 1 && history[i].time > 0; i++) {
+ logToPrinter(printer, history[i]);
+ handOff();
+ }
+ for (uint16_t i = 0; i < historyPtr; i++) {
+ logToPrinter(printer, history[i]);
+ handOff();
+ }
+ printer.println("LOG END");
+}
+// dirty but we need avoid a timeout in controllers due to long serial processing
+void Logger::handOff() {
+ tickHandler.process();
+ canHandlerEv.process();
+ canHandlerCar.process();
}
diff --git a/Logger.h b/Logger.h
index 436a4e0..d49e88d 100644
--- a/Logger.h
+++ b/Logger.h
@@ -30,33 +30,62 @@
#include
#include "config.h"
#include "DeviceTypes.h"
-#include "constants.h"
-class Logger {
+#define HISTORY_SIZE 100
+
+class Device;
+
+class Logger
+{
public:
- enum LogLevel {
- Debug = 0, Info = 1, Warn = 2, Error = 3, Off = 4
- };
- static void debug(char *, ...);
- static void debug(DeviceId, char *, ...);
- static void info(char *, ...);
- static void info(DeviceId, char *, ...);
- static void warn(char *, ...);
- static void warn(DeviceId, char *, ...);
- static void error(char *, ...);
- static void error(DeviceId, char *, ...);
- static void console(char *, ...);
- static void setLoglevel(LogLevel);
- static LogLevel getLogLevel();
- static uint32_t getLastLogTime();
- static boolean isDebug();
+ enum LogLevel
+ {
+ Debug = 0,
+ Info = 1,
+ Warn = 2,
+ Error = 3,
+ Off = 4
+ };
+ struct LogEntry {
+ uint32_t time;
+ LogLevel level;
+ String deviceName;
+ String message;
+ };
+ Logger();
+ void debug(String, ...);
+ void debug(Device *, String, ...);
+ void info(String, ...);
+ void info(Device *, String, ...);
+ void warn(String, ...);
+ void warn(Device *, String, ...);
+ void error(String, ...);
+ void error(Device *, String, ...);
+ void console(String, ...);
+ void setLoglevel(LogLevel);
+ void setLoglevel(Device *, LogLevel);
+ LogLevel getLogLevel();
+ LogLevel getLogLevel(Device *);
+ LogEntry &createLogEntry(LogLevel level, String deviceName, String message);
+ String logLevelToString(LogLevel level);
+ boolean isDebug();
+ void printHistory(Print &printer);
private:
- static LogLevel logLevel;
- static uint32_t lastLogTime;
+ LogLevel logLevel;
+ bool debugging;
+ LogLevel *deviceLoglevel;
+ char msgBuffer[LOG_BUFFER_SIZE];
+ uint16_t lastMsgRepeated;
+ uint32_t repeatStart;
+ LogEntry history[HISTORY_SIZE];
+ uint16_t historyPtr;
- static void log(DeviceId, LogLevel, char *format, va_list);
- static void logMessage(char *format, va_list args);
- static void printDeviceName(DeviceId);
+ void log(String, LogLevel, String format, va_list);
+ void logToPrinter(Print &printer, LogEntry &logEntry);
+ void logToWifi(LogEntry &logEntry);
+ void handOff();
};
+extern Logger logger;
+
#endif /* LOGGER_H_ */
diff --git a/MemCache.cpp b/MemCache.cpp
index 3c94958..859f881 100644
--- a/MemCache.cpp
+++ b/MemCache.cpp
@@ -1,7 +1,7 @@
/*
* MemCache.cpp
*
-Copyright (c) 2014 Collin Kidder, Michael Neuweiler, Charles Galpin
+Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
Permission is hereby granted, free of charge, to any person obtaining
a copy of this software and associated documentation files (the
@@ -26,379 +26,500 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
#include "MemCache.h"
+MemCache memCache;
+
MemCache::MemCache()
{
}
-void MemCache::setup() {
- TickHandler::getInstance()->detach(this);
- for (U8 c = 0; c < NUM_CACHED_PAGES; c++) {
- pages[c].address = 0xFFFFFF; //maximum number. This is way over what our chip will actually support so it signals unused
- pages[c].age = 0;
- pages[c].dirty = false;
- }
- //WriteTimer = 0;
-
- //digital pin 19 is connected to the write protect function of the EEPROM. It is active high so set it low to enable writes
- pinMode(19, OUTPUT);
- digitalWrite(19, LOW);
- TickHandler::getInstance()->attach(this, CFG_TICK_INTERVAL_MEM_CACHE);
+MemCache::~MemCache()
+{
}
+/*
+ * Initialize the memory cache (note, this is only a TickListener, not a device !)
+ */
+void MemCache::setup()
+{
+ tickHandler.detach(this);
+
+ logger.debug("add MemCache (id: %#x, %#x)", MEMCACHE, &memCache);
+
+ Wire.begin();
+ for (U8 c = 0; c < NUM_CACHED_PAGES; c++) {
+ pages[c].address = 0xFFFFFF; //maximum number. This is way over what our chip will actually support so it signals unused
+ pages[c].age = 0;
+ pages[c].dirty = false;
+ }
+
+ //WriteTimer = 0;
+
+ //digital pin 18 (GEVCU 2) 19 (GEVCU>=3) is connected to the write protect function of the EEPROM. It is active high so set it low to enable writes
+ pinMode(CFG_EEPROM_WRITE_PROTECT, OUTPUT);
+ digitalWrite(CFG_EEPROM_WRITE_PROTECT, LOW);
+
+ tickHandler.attach(this, CFG_TICK_INTERVAL_MEM_CACHE);
+}
-//Handle aging of dirty pages and flushing of aged out dirty pages
+/*
+ * Handle aging of dirty pages and flushing of aged out dirty pages
+ */
void MemCache::handleTick()
{
- U8 c;
- cache_age();
- for (c=0;c> 8; //kick it down to the page we're talking about
- c = cache_hit(addr);
- if (c != 0xFF) FlushPage(c);
+/*
+ * Flush a given page by the page ID.
+ * This is NOT by address so act accordingly.
+ */
+void MemCache::FlushPage(uint8_t page)
+{
+ if (pages[page].dirty) {
+ cache_writepage(page);
+ pages[page].dirty = false;
+ pages[page].age = 0; //freshly flushed!
+ }
}
-//Like FlushPage but also marks the page invalid (unused) so if another read request comes it it'll have to be re-read from EEPROM
+/*
+ * Like FlushPage but also marks the page invalid (unused).
+ * So if another read request comes it it'll have to be re-read from EEPROM
+ */
void MemCache::InvalidatePage(uint8_t page)
{
- if (page > NUM_CACHED_PAGES - 1) return; //invalid page, buddy!
- if (pages[page].dirty) {
- cache_writepage(page);
- }
- pages[page].dirty = false;
- pages[page].address = 0xFFFFFF;
- pages[page].age = 0;
+ if (page > NUM_CACHED_PAGES - 1) {
+ return; //invalid page, buddy!
+ }
+
+ if (pages[page].dirty) {
+ cache_writepage(page);
+ }
+
+ pages[page].dirty = false;
+ pages[page].address = 0xFFFFFF;
+ pages[page].age = 0;
}
-//Mark a given page unused given an address within that page. Will write the page out if it was dirty.
+/*
+ * Mark a given page unused given an address within that page.
+ * Will write the page out if it was dirty.
+ */
void MemCache::InvalidateAddress(uint32_t address)
{
- uint32_t addr;
- uint8_t c;
+ uint32_t addr;
+ uint8_t c;
+
+ addr = address >> 8; //kick it down to the page we're talking about
+ c = cache_hit(addr);
- addr = address >> 8; //kick it down to the page we're talking about
- c = cache_hit(addr);
- if (c != 0xFF) InvalidatePage(c);
+ if (c != 0xFF) {
+ InvalidatePage(c);
+ }
}
-//Mark all page cache entries unused (go back to clean slate). It will try to write any dirty pages so be prepared to wait.
+/*
+ * Mark all page cache entries unused (go back to clean slate).
+ * It will try to write any dirty pages so be prepared to wait.
+ */
void MemCache::InvalidateAll()
{
- uint8_t c;
- for (c=0;c> 8; //kick it down to the page we're talking about
- thisCache = cache_hit(page_addr);
+ page_addr = address >> 8; //kick it down to the page we're talking about
+ thisCache = cache_hit(page_addr);
- if (thisCache != 0xFF) { //if we did indeed have that page in cache
- pages[thisCache].age = MAX_AGE;
- }
+ if (thisCache != 0xFF) { //if we did indeed have that page in cache
+ pages[thisCache].age = MAX_AGE;
+ }
}
-//Write data into the memory cache. Takes the place of direct EEPROM writes
-//There are lots of versions of this
+/*
+ * Write data into the memory cache instead of direct EEPROM writes
+ */
boolean MemCache::Write(uint32_t address, uint8_t valu)
{
- uint32_t addr;
- uint8_t c;
-
- addr = address >> 8; //kick it down to the page we're talking about
- c = cache_hit(addr);
- if (c == 0xFF) {
- c = cache_findpage(); //try to free up a page
- if (c != 0xFF) c = cache_readpage(addr); //and populate it with the existing data
- }
- if (c != 0xFF) {
- pages[c].data[(uint16_t)(address & 0x00FF)] = valu;
- pages[c].dirty = true;
- pages[c].address = addr; //set this in case we actually are setting up a new cache page
- return true;
- }
- return false;
+ uint32_t addr;
+ uint8_t c;
+
+ addr = address >> 8; //kick it down to the page we're talking about
+ c = cache_hit(addr);
+
+ if (c == 0xFF) {
+ c = cache_findpage(); //try to free up a page
+
+ if (c != 0xFF) {
+ c = cache_readpage(addr); //and populate it with the existing data
+ }
+ }
+
+ if (c != 0xFF) {
+ pages[c].data[(uint16_t)(address & 0x00FF)] = valu;
+ pages[c].dirty = true;
+ pages[c].address = addr; //set this in case we actually are setting up a new cache page
+ return true;
+ }
+
+ return false;
}
+/*
+ * Write data into the memory cache instead of direct EEPROM writes
+ */
boolean MemCache::Write(uint32_t address, uint16_t valu)
{
- boolean result;
- result = Write(address, &valu, 2);
- return result;
+ boolean result;
+ result = Write(address, &valu, 2);
+ return result;
}
+/*
+ * Write data into the memory cache instead of direct EEPROM writes
+ */
boolean MemCache::Write(uint32_t address, uint32_t valu)
{
- boolean result;
- result = Write(address, &valu, 4);
- return result;
+ boolean result;
+ result = Write(address, &valu, 4);
+ return result;
}
+/*
+ * Write data into the memory cache instead of direct EEPROM writes
+ */
boolean MemCache::Write(uint32_t address, void* data, uint16_t len)
{
- uint32_t addr;
- uint8_t c;
- uint16_t count;
-
- for (count = 0; count < len; count++) {
- addr = (address+count) >> 8; //kick it down to the page we're talking about
- c = cache_hit(addr);
- if (c == 0xFF) {
- c = cache_findpage(); //try to find a page that either isn't loaded or isn't dirty
- if (c != 0xFF) c = cache_readpage(addr); //and populate it with the existing data
+ uint32_t addr;
+ uint8_t c;
+ uint16_t count;
+
+ for (count = 0; count < len; count++) {
+ addr = (address + count) >> 8; //kick it down to the page we're talking about
+ c = cache_hit(addr);
+
+ if (c == 0xFF) {
+ c = cache_findpage(); //try to find a page that either isn't loaded or isn't dirty
+
+ if (c != 0xFF) {
+ c = cache_readpage(addr); //and populate it with the existing data
+ }
+ }
+
+ if (c != 0xFF) { //could we find a suitable cache page to write to?
+ pages[c].data[(uint16_t)((address + count) & 0x00FF)] = * (uint8_t *)(data + count);
+ pages[c].dirty = true;
+ pages[c].address = addr; //set this in case we actually are setting up a new cache page
+ } else {
+ break;
+ }
}
- if (c != 0xFF) { //could we find a suitable cache page to write to?
- pages[c].data[(uint16_t)((address+count) & 0x00FF)] = *(uint8_t *)(data + count);
- pages[c].dirty = true;
- pages[c].address = addr; //set this in case we actually are setting up a new cache page
+
+ if (c != 0xFF) {
+ return true; //all ok!
}
- else break;
- }
- if (c != 0xFF) return true; //all ok!
- return false;
+ return false;
}
+/*
+ * Read a value from the cache.
+ * If not available in the cache, the EEPROM will be read.
+ */
boolean MemCache::Read(uint32_t address, uint8_t* valu)
{
- uint32_t addr;
- uint8_t c;
-
- addr = address >> 8; //kick it down to the page we're talking about
- c = cache_hit(addr);
-
- if (c == 0xFF) { //page isn't cached. Search the cache, potentially dump a page and bring this one in
- c = cache_readpage(addr);
- }
-
- if (c != 0xFF) {
- *valu = pages[c].data[(uint16_t)(address & 0x00FF)];
- if (!pages[c].dirty) pages[c].age = 0; //reset age since we just used it
- return true; //all ok!
- }
- else {
- return false;
- }
+ uint32_t addr;
+ uint8_t c;
+
+ addr = address >> 8; //kick it down to the page we're talking about
+ c = cache_hit(addr);
+
+ if (c == 0xFF) { //page isn't cached. Search the cache, potentially dump a page and bring this one in
+ c = cache_readpage(addr);
+ }
+
+ if (c != 0xFF) {
+ *valu = pages[c].data[(uint16_t)(address & 0x00FF)];
+
+ if (!pages[c].dirty) {
+ pages[c].age = 0; //reset age since we just used it
+ }
+
+ return true; //all ok!
+ } else {
+ return false;
+ }
}
+/*
+ * Read a value from the cache.
+ * If not available in the cache, the EEPROM will be read.
+ */
boolean MemCache::Read(uint32_t address, uint16_t* valu)
{
- boolean result;
- result = Read(address, valu, 2);
- return result;
+ boolean result;
+ result = Read(address, valu, 2);
+ return result;
}
+/*
+ * Read a value from the cache.
+ * If not available in the cache, the EEPROM will be read.
+ */
boolean MemCache::Read(uint32_t address, uint32_t* valu)
{
- boolean result;
- result = Read(address, valu, 4);
- return result;
+ boolean result;
+ result = Read(address, valu, 4);
+ return result;
}
+/*
+ * Read a value from the cache.
+ * If not available in the cache, the EEPROM will be read.
+ */
boolean MemCache::Read(uint32_t address, void* data, uint16_t len)
{
- uint32_t addr;
- uint8_t c;
- uint16_t count;
+ uint32_t addr;
+ uint8_t c;
+ uint16_t count;
+
+ for (count = 0; count < len; count++) {
+ addr = (address + count) >> 8;
+ c = cache_hit(addr);
+
+ if (c == 0xFF) { //page isn't cached. Search the cache, potentially dump a page and bring this one in
+ c = cache_readpage(addr);
+ }
+
+ if (c != 0xFF) {
+ * (uint8_t *)(data + count) = pages[c].data[(uint16_t)((address + count) & 0x00FF)];
+
+ if (!pages[c].dirty) {
+ pages[c].age = 0; //reset age since we just used it
+ }
+ } else {
+ break; //bust the for loop if we run into trouble
+ }
+ }
- for (count = 0; count < len; count++) {
- addr = (address + count) >> 8;
- c = cache_hit(addr);
- if (c == 0xFF) { //page isn't cached. Search the cache, potentially dump a page and bring this one in
- c = cache_readpage(addr);
- }
if (c != 0xFF) {
- *(uint8_t *)(data + count) = pages[c].data[(uint16_t)((address+count) & 0x00FF)];
- if (!pages[c].dirty) pages[c].age = 0; //reset age since we just used it
+ return true; //all ok!
}
- else break; //bust the for loop if we run into trouble
- }
-
- if (c != 0xFF) return true; //all ok!
- return false;
-}
-boolean MemCache::isWriting()
-{
- //if (WriteTimer) return true;
- return false;
+ return false;
}
+/*
+ * Find page number of an address (if present, return 0xFF otherwise)
+ */
uint8_t MemCache::cache_hit(uint32_t address)
{
- uint8_t c;
- for (c = 0; c < NUM_CACHED_PAGES; c++) {
- if (pages[c].address == address) {
- return c;
- }
- }
- return 0xFF;
+ uint8_t c;
+
+ for (c = 0; c < NUM_CACHED_PAGES; c++) {
+ if (pages[c].address == address) {
+ return c;
+ }
+ }
+
+ return 0xFF;
}
+/*
+ * Increase the age of all cached pages
+ */
void MemCache::cache_age()
{
- uint8_t c;
- for (c = 0; c < NUM_CACHED_PAGES; c++) {
- if (pages[c].age < MAX_AGE) {
- pages[c].age++;
+ uint8_t c;
+
+ for (c = 0; c < NUM_CACHED_PAGES; c++) {
+ if (pages[c].age < MAX_AGE) {
+ pages[c].age++;
+ }
}
- }
}
-//try to find an empty page or one that can be removed from cache
+/*
+ * Try to find an empty page or one that can be removed from cache
+ */
uint8_t MemCache::cache_findpage()
{
- uint8_t c;
- uint8_t old_c, old_v;
- for (c=0;c= old_v) {
- old_c = c;
- old_v = pages[c].age;
- }
- }
- if (old_c == 0xFF) { //no pages were not dirty - try to free one up
- FlushSinglePage(); //try to free up a page
- //now try to find the free page (if one was freed)
+
+ //if we got here then there are no free pages so scan to find the oldest one which isn't dirty
+ old_c = 0xFF;
old_v = 0;
- for (c=0;c= old_v) {
- old_c = c;
- old_v = pages[c].age;
- }
+
+ for (c = 0; c < NUM_CACHED_PAGES; c++) {
+ if (!pages[c].dirty && pages[c].age >= old_v) {
+ old_c = c;
+ old_v = pages[c].age;
+ }
+ }
+
+ if (old_c == 0xFF) { //no pages were not dirty - try to free one up
+ FlushSinglePage(); //try to free up a page
+ //now try to find the free page (if one was freed)
+ old_v = 0;
+
+ for (c = 0; c < NUM_CACHED_PAGES; c++) {
+ if (!pages[c].dirty && pages[c].age >= old_v) {
+ old_c = c;
+ old_v = pages[c].age;
+ }
+ }
+
+ if (old_c == 0xFF) {
+ return 0xFF; //if nothing worked then give up
+ }
}
- if (old_c == 0xFF) return 0xFF; //if nothing worked then give up
- }
- //If we got to this point then we have a page to use
- pages[old_c].age = 0;
- pages[old_c].dirty = false;
- pages[old_c].address = 0xFFFFFF; //mark it unused
+ //If we got to this point then we have a page to use
+ pages[old_c].age = 0;
+ pages[old_c].dirty = false;
+ pages[old_c].address = 0xFFFFFF; //mark it unused
- return old_c;
+ return old_c;
}
+/*
+ * Find the page of the cache and read data directly from the EEPROM into it.
+ */
uint8_t MemCache::cache_readpage(uint32_t addr)
{
- uint16_t c,d,e;
- uint32_t address = addr << 8;
- uint8_t buffer[3];
- uint8_t i2c_id;
- c = cache_findpage();
-// Logger::debug("r");
- if (c != 0xFF) {
- buffer[0] = ((address & 0xFF00) >> 8);
- //buffer[1] = (address & 0x00FF);
- buffer[1] = 0; //the pages are 256 bytes so the start of a page is always 00 for the LSB
- i2c_id = 0b01010000 + ((address >> 16) & 0x03); //10100 is the chip ID then the two upper bits of the address
- Wire.beginTransmission(i2c_id);
- Wire.write(buffer, 2);
- Wire.endTransmission(false); //do NOT generate stop
- //delayMicroseconds(50); //give TWI some time to send and chip some time to get page
- Wire.requestFrom(i2c_id, 256); //this will generate stop though.
- for (e = 0; e < 256; e++)
- {
- if(Wire.available())
- {
- d = Wire.read(); // receive a byte as character
- pages[c].data[e] = d;
- }
- }
- pages[c].address = addr;
- pages[c].age = 0;
- pages[c].dirty = false;
- }
- return c;
+ uint16_t c, d, e;
+ uint32_t address = addr << 8;
+ uint8_t buffer[3];
+ uint8_t i2c_id;
+ c = cache_findpage();
+
+ if (c != 0xFF) {
+ logger.debug("reading page %d from eeprom address %d", c, addr);
+
+ buffer[0] = ((address & 0xFF00) >> 8);
+ //buffer[1] = (address & 0x00FF);
+ buffer[1] = 0; //the pages are 256 bytes so the start of a page is always 00 for the LSB
+ i2c_id = 0b01010000 + ((address >> 16) & 0x03); //10100 is the chip ID then the two upper bits of the address
+ Wire.beginTransmission(i2c_id);
+ Wire.write(buffer, 2);
+ Wire.endTransmission(false); //do NOT generate stop
+ //delayMicroseconds(50); //give TWI some time to send and chip some time to get page
+ Wire.requestFrom(i2c_id, 256); //this will generate stop though.
+
+ for (e = 0; e < 256; e++) {
+ if (Wire.available()) {
+ d = Wire.read(); // receive a byte as character
+ pages[c].data[e] = d;
+ }
+ }
+
+ pages[c].address = addr;
+ pages[c].age = 0;
+ pages[c].dirty = false;
+ }
+
+ return c;
}
+/*
+ * Write a page from the memory cache directly to the EEPROM
+ */
boolean MemCache::cache_writepage(uint8_t page)
{
- uint16_t d;
- uint32_t addr;
- uint8_t buffer[258];
- uint8_t i2c_id;
- addr = pages[page].address << 8;
- buffer[0] = ((addr & 0xFF00) >> 8);
- //buffer[1] = (addr & 0x00FF);
- buffer[1] = 0; //pages are 256 bytes so LSB is always 0 for the start of a page
- i2c_id = 0b01010000 + ((addr >> 16) & 0x03); //10100 is the chip ID then the two upper bits of the address
- for (d = 0; d < 256; d++) {
- buffer[d + 2] = pages[page].data[d];
- }
- Wire.beginTransmission(i2c_id);
- Wire.write(buffer, 258);
- Wire.endTransmission(true);
- return true;
+ uint16_t d;
+ uint32_t addr;
+ uint8_t buffer[258];
+ uint8_t i2c_id;
+ addr = pages[page].address << 8;
+ buffer[0] = ((addr & 0xFF00) >> 8);
+ //buffer[1] = (addr & 0x00FF);
+ buffer[1] = 0; //pages are 256 bytes so LSB is always 0 for the start of a page
+ i2c_id = 0b01010000 + ((addr >> 16) & 0x03); //10100 is the chip ID then the two upper bits of the address
+
+ logger.debug("flushing page %d to eeprom address %d", page, pages[page].address);
+
+ for (d = 0; d < 256; d++) {
+ buffer[d + 2] = pages[page].data[d];
+ }
+
+ Wire.beginTransmission(i2c_id);
+ Wire.write(buffer, 258);
+ Wire.endTransmission(true);
+
+ return true;
}
diff --git a/MemCache.h b/MemCache.h
index 8200ba4..1d7bc12 100644
--- a/MemCache.h
+++ b/MemCache.h
@@ -3,28 +3,28 @@
*
* Handles caching of EEPROM pages to RAM
*
-Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
+ Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
-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:
+ 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 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.
+ 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 MEM_CACHE_H_
#define MEM_CACHE_H_
@@ -35,67 +35,67 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
#include
//Total # of allowable pages to cache. Limits RAM usage
-#define NUM_CACHED_PAGES 16
+#define NUM_CACHED_PAGES 20
//maximum allowable age of a cache
#define MAX_AGE 128
/* # of system ticks per aging cycle. There are 128 aging levels total so
-// multiply 128 by this aging period and multiple that by system tick duration
-// to determine how long it will take for a page to age out fully and get written
-// if dirty. For instance, 128 levels * 500 aging period * 10ms (100Hz tick) = 640 seconds
-// EEPROM handles about 1 million write cycles. So, a flush time of 100 seconds means that
-// continuous writing would last 100M seconds which is 3.17 years
-// Another way to look at it is that 128 aging levels * 40ms tick is 5.12 seconds to flush for
-// each aging period below. Adjust acccordingly.
-*/
-#define AGING_PERIOD 60
-
-//Current parameters as of Sept 7 2014 = 128 * 40ms * 60 = 307.2 seconds to flush = about 10 years EEPROM life
-
-class MemCache: public TickObserver {
- public:
- void setup();
- void handleTick();
- void FlushSinglePage();
- void FlushAllPages();
- void FlushPage(uint8_t page);
- void FlushAddress(uint32_t address);
- void InvalidatePage(uint8_t page);
- void InvalidateAddress(uint32_t address);
- void InvalidateAll();
- void AgeFullyPage(uint8_t page);
- void AgeFullyAddress(uint32_t address);
-
- boolean Write(uint32_t address, uint8_t valu);
- boolean Write(uint32_t address, uint16_t valu);
- boolean Write(uint32_t address, uint32_t valu);
- boolean Write(uint32_t address, void* data, uint16_t len);
-
- //It's sort of weird to make the read function take a reference but it allows for overloading
- boolean Read(uint32_t address, uint8_t* valu);
- boolean Read(uint32_t address, uint16_t* valu);
- boolean Read(uint32_t address, uint32_t* valu);
- boolean Read(uint32_t address, void* data, uint16_t len);
-
- MemCache();
-
- private:
- typedef struct {
- uint8_t data[256];
- uint32_t address; //address of start of page
- uint8_t age; //
- boolean dirty;
- } PageCache;
-
- PageCache pages[NUM_CACHED_PAGES];
- boolean isWriting();
- uint8_t cache_hit(uint32_t address);
- void cache_age();
- uint8_t cache_findpage();
- uint8_t cache_readpage(uint32_t addr);
- boolean cache_writepage(uint8_t page);
- uint8_t agingTimer;
+ // multiply 128 by this aging period and multiple that by system tick duration
+ // to determine how long it will take for a page to age out fully and get written
+ // if dirty. For instance, 128 levels * 500 aging period * 10ms (100Hz tick) = 640 seconds
+ // EEPROM handles about 1 million write cycles. So, a flush time of 100 seconds means that
+ // continuous writing would last 100M seconds which is 3.17 years
+ // Another way to look at it is that 128 aging levels * 40ms tick is 5.12 seconds to flush for
+ // each aging period below. Adjust accordingly.
+ */
+
+class MemCache: public TickObserver
+{
+public:
+ void setup();
+ void handleTick();
+ void FlushSinglePage();
+ void FlushAllPages();
+ void FlushPage(uint8_t page);
+ void FlushAddress(uint32_t address);
+ void InvalidatePage(uint8_t page);
+ void InvalidateAddress(uint32_t address);
+ void InvalidateAll();
+ void AgeFullyPage(uint8_t page);
+ void AgeFullyAddress(uint32_t address);
+
+ boolean Write(uint32_t address, uint8_t valu);
+ boolean Write(uint32_t address, uint16_t valu);
+ boolean Write(uint32_t address, uint32_t valu);
+ boolean Write(uint32_t address, void* data, uint16_t len);
+
+ //It's sort of weird to make the read function take a reference but it allows for overloading
+ boolean Read(uint32_t address, uint8_t* valu);
+ boolean Read(uint32_t address, uint16_t* valu);
+ boolean Read(uint32_t address, uint32_t* valu);
+ boolean Read(uint32_t address, void* data, uint16_t len);
+
+ MemCache();
+ virtual ~MemCache();
+
+private:
+ typedef struct
+ {
+ uint8_t data[256];
+ uint32_t address; //address of start of page
+ uint8_t age; //
+ boolean dirty;
+ } PageCache;
+
+ PageCache pages[NUM_CACHED_PAGES];
+ uint8_t cache_hit(uint32_t address);
+ void cache_age();
+ uint8_t cache_findpage();
+ uint8_t cache_readpage(uint32_t addr);
+ boolean cache_writepage(uint8_t page);
};
+extern MemCache memCache;
+
#endif /* MEM_CACHE_H_ */
diff --git a/MotorController.cpp b/MotorController.cpp
index 67d6fdd..38db928 100644
--- a/MotorController.cpp
+++ b/MotorController.cpp
@@ -3,625 +3,691 @@
*
* Parent class for all motor controllers.
*
-Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
-
-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.
-
- */
-
+ Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
+
+ 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 "MotorController.h"
-
-MotorController::MotorController() : Device() {
- ready = false;
- running = false;
- faulted = false;
- warning = false;
-
- temperatureMotor = 0;
- temperatureInverter = 0;
- temperatureSystem = 0;
-
- statusBitfield1 = 0;
- statusBitfield2 = 0;
- statusBitfield3 = 0;
- statusBitfield4 = 0;
-
- powerMode = modeTorque;
- throttleRequested = 0;
- speedRequested = 0;
- speedActual = 0;
- torqueRequested = 0;
- torqueActual = 10;
- torqueAvailable = 0;
- mechanicalPower = 0;
-
- selectedGear = NEUTRAL;
- operationState=ENABLE;
-
- dcVoltage = 0;
- dcCurrent = 0;
- acCurrent = 0;
- kiloWattHours = 0;
- nominalVolts = 0;
-
- donePrecharge = false;
- prelay = false;
- coolflag = false;
- skipcounter=0;
- testenableinput=0;
- testreverseinput=0;
- premillis=0;
-
-
-
-}
-
-void MotorController::setup() {
-
- MotorControllerConfiguration *config = (MotorControllerConfiguration *)getConfiguration();
- statusBitfield1 = 0;
- statusBitfield2 = 0;
- statusBitfield3 = 0;
- statusBitfield4 = 0;
- prefsHandler->read(EEMC_KILOWATTHRS, &kiloWattHours); //retrieve kilowatt hours from EEPROM
- nominalVolts=config->nominalVolt;
- donePrecharge=false;
- premillis=millis();
-
- if(config->prechargeR==12345)
- {
- torqueActual=2;
- dcCurrent=1501;
- dcVoltage=3320;
-
- }
- Logger::console("PRELAY=%i - Current PreCharge Relay output", config->prechargeRelay);
- Logger::console("MRELAY=%i - Current Main Contactor Relay output", config->mainContactorRelay);
- Logger::console("PREDELAY=%i - Precharge delay time", config->prechargeR);
-
- //show our work
- Logger::console("PRECHARGING...DOUT0:%d, DOUT1:%d, DOUT2:%d, DOUT3:%d,DOUT4:%d, DOUT5:%d, DOUT6:%d, DOUT7:%d", getOutput(0), getOutput(1), getOutput(2), getOutput(3),getOutput(4), getOutput(5), getOutput(6), getOutput(7));
- coolflag=false;
-
- Device::setup();
-
-}
-
-
-void MotorController::handleTick() {
-
- MotorControllerConfiguration *config = (MotorControllerConfiguration *)getConfiguration();
-
- //Set status annunciators
- if(ready) statusBitfield1 |=1 << 15;else statusBitfield1 &= ~(1 <<15);
- if(running) statusBitfield1 |=1 << 14;else statusBitfield1 &= ~(1 <<14);
- if(warning) statusBitfield1 |=1 << 10;else statusBitfield1 &= ~(1 <<10);
- if(faulted) statusBitfield1 |=1 << 9;else statusBitfield1 &= ~(1 <<9);
-
- //Calculate killowatts and kilowatt hours
- mechanicalPower=dcVoltage*dcCurrent/10000; //In kilowatts. DC voltage is x10
- if (dcVoltage>nominalVolts && torqueActual>0) {kiloWattHours=1;} //If our voltage is higher than fully charged with no regen, zero our kwh meter
- if (milliStamp>millis()) {milliStamp=0;} //In case millis rolls over to zero while running
- kiloWattHours+=(millis()-milliStamp)*mechanicalPower;//We assume here that power is at current level since last tick and accrue in kilowattmilliseconds.
- milliStamp=millis(); //reset our kwms timer for next check
-
-
- //Throttle check
- Throttle *accelerator = DeviceManager::getInstance()->getAccelerator();
- Throttle *brake = DeviceManager::getInstance()->getBrake();
- if (accelerator)
- throttleRequested = accelerator->getLevel();
- if (brake && brake->getLevel() < -10 && brake->getLevel() < accelerator->getLevel()) //if the brake has been pressed it overrides the accelerator.
- throttleRequested = brake->getLevel();
- //Logger::debug("Throttle: %d", throttleRequested);
-
-
- if (!donePrecharge)checkPrecharge();
-
-
- if(skipcounter++ > 30) //A very low priority loop for checks that only need to be done once per second.
- {
- skipcounter=0; //Reset our laptimer
-
-
- //Some test simulations if precharge time is set to 12345
- if(config->prechargeR==12345)
- {
- dcVoltage--;
- if (torqueActual < -500)
- {
- torqueActual=20;
- }
- else
- {
- torqueActual=-650;
- }
- if (dcCurrent < 0)
- {
- dcCurrent=120;
- }
- else
- {
- dcCurrent=-65;
- }
- if (temperatureInverter < config->coolOn*10)
- {
- temperatureInverter=(config->coolOn+2)*10;
- }
- else
- {
- temperatureInverter=(config->coolOff-2)*10;
- }
-
- if (throttleRequested < 500)
- {
- throttleRequested=500;
- }
- else
- {
- throttleRequested=0;
- }
- if(testenableinput)
- {
- testenableinput=false;
- }
- else
- {
- testenableinput=true;
- }
-
- if(testreverseinput)
- {
- testreverseinput=false;
- }
- else
- {
- testreverseinput=true;
- }
- }
- coolingcheck();
- checkBrakeLight();
- checkEnableInput();
- checkReverseInput();
- checkReverseLight();
-
- //Store kilowatt hours, but only once in awhile.
- prefsHandler->write(EEMC_KILOWATTHRS, kiloWattHours);
- prefsHandler->saveChecksum();
-
- }
-}
-
-
-void MotorController::checkPrecharge()
-{
-
- int prechargetime=getprechargeR();
- int contactor=getmainContactorRelay();
- int relay=getprechargeRelay();
-
- if (relay>7 || relay<0 || contactor<0 || contactor>7) //We don't have a contactor and a precharge relay
- {
- donePrecharge=true; //Let's end this charade.
- return;
- }
-
- if ((millis()-premillis)< prechargetime) //Check milliseconds since startup against our entered delay in milliseconds
- {
- if(!prelay)
- {
- setOutput(contactor, 0); //Make sure main contactor off
- statusBitfield2 &= ~(1 << 17); //clear bitTurn off MAIN CONTACTOR annunciator
- statusBitfield1 &= ~(1 << contactor);//clear bitTurn off main contactor output annunciator
- setOutput(relay, 1); //ok. Turn on precharge relay
- statusBitfield2 |=1 << 19; //set bit to turn on PRECHARGE RELAY annunciator
- statusBitfield1 |=1 << relay; //set bit to turn ON precharge OUTPUT annunciator
- throttleRequested = 0; //Keep throttle at zero during precharge
- prelay=true;
- Logger::info("Starting precharge sequence - wait %i milliseconds", prechargetime);
-
- }
- }
- else
- {
- setOutput(contactor, 1); //Main contactor on
- statusBitfield2 |=1 << 17; //set bit to turn on MAIN CONTACTOR annunciator
- statusBitfield1 |=1 << contactor;//setbit to Turn on main contactor output annunciator
- Logger::info("Precharge sequence complete after %i milliseconds", prechargetime);
- Logger::info("MAIN CONTACTOR ENABLED...DOUT0:%d, DOUT1:%d, DOUT2:%d, DOUT3:%d,DOUT4:%d, DOUT5:%d, DOUT6:%d, DOUT7:%d", getOutput(0), getOutput(1), getOutput(2), getOutput(3),getOutput(4), getOutput(5), getOutput(6), getOutput(7));
- donePrecharge=true; //Time's up. Let's don't do ANY of this on future ticks.
- //Generally, we leave the precharge relay on. This doesn't hurt much in any configuration. But when using two contactors
- //one positive with a precharge resistor and one on the negative leg to act as precharge, we need to leave precharge on.
-
- }
+
+MotorController::MotorController() :
+ Device()
+{
+ temperatureMotor = 0;
+ temperatureController = 0;
+
+ powerOn = false;
+ gear = GEAR_NEUTRAL;
+
+ throttleLevel = 0;
+ speedRequested = 0;
+ speedActual = 0;
+ torqueRequested = 0;
+ torqueActual = 0;
+ torqueAvailable = 0;
+
+ dcVoltage = 0;
+ dcCurrent = 0;
+ acCurrent = 0;
+ slewTimestamp = millis();
+ gearChangeTimestamp = 0;
+ rolling = false;
+ ticksNoMessage = 0;
+ brakeHoldActive = false;
+ brakeHoldStart = 0;
+ brakeHoldLevel = 0;
+ minimumBatteryTemperature = 50; // 5 deg C
+
+ cruisePid = NULL;
+ cruiseSpeedActual = 0;
+ cruiseSpeedTarget = 0;
+ cruiseThrottle = 1000;
+ cruiseSpeedLast = 0;
+ cruiseSpeedBufferPtr = 0;
+ cruiseSpeedSum = 0;
+ cruiseControlEnabled = false;
+ cruiseLastButton = NONE;
+ cruiseButtonPressed = 0;
+}
+
+DeviceType MotorController::getType()
+{
+ return (DEVICE_MOTORCTRL);
}
-//This routine is used to set an optional cooling fan output to on if the current temperature
-//exceeds a specified value. Annunciators are set on website to indicate status.
-void MotorController::coolingcheck()
- {
- int coolfan=getCoolFan();
-
- if(coolfan>=0 and coolfan<8) //We have 8 outputs 0-7 If they entered something else, there is no point in doing this check.
- {
- if(temperatureInverter/10>getCoolOn()) //If inverter temperature greater than COOLON, we want to turn on the coolingoutput
- {
- if(!coolflag)
- {
- coolflag=1;
- setOutput(coolfan, 1); //Turn on cooling fan output
- statusBitfield1 |=1 << coolfan; //set bit to turn on cooling fan output annunciator
- statusBitfield3 |=1 << 9; //Set bit to turn on OVERTEMP annunciator
- }
- }
-
- if(temperatureInverter/10=0 && getBrakeLight()<8) //If we have one configured ie NOT 255 but a valid output
- {
- int brakelight=getBrakeLight(); //Get brakelight output once
-
- if(getTorqueActual() < -100) //We only want to turn on brake light if we are have regen of more than 10 newton meters
- {
- setOutput(brakelight, 1); //Turn on brake light output
- statusBitfield1 |=1 << brakelight; //set bit to turn on brake light output annunciator
- }
- else
- {
- setOutput(brakelight, 0); //Turn off brake light output
- statusBitfield1 &= ~(1 << brakelight);//clear bit to turn off brake light output annunciator
- }
- }
-
-}
-
-//If a reverse light output is configured, this will turn it on anytime the gear state is in REVERSE
-void MotorController::checkReverseLight()
-{
- uint16_t reverseLight=getRevLight();
- if(reverseLight >=0 && reverseLight <8) //255 means none selected. We don't have a reverselight output configured.
- {
- if(selectedGear==REVERSE) //If the selected gear IS reverse
- {
- setOutput(reverseLight, true); //Turn on reverse light output
- statusBitfield1 |=1 << reverseLight; //set bit to turn on reverse light output annunciator
- }
- else
- {
- setOutput(reverseLight, false); //Turn off reverse light output
- statusBitfield1 &= ~(1 << reverseLight);//clear bit to turn off reverselight OUTPUT annunciator
- }
+/*
+ * Activate/Deactivate status indicator at standstill/rolling
+ */
+void MotorController::updateStatusIndicator()
+{
+ if (running) {
+ if (speedActual == 0) {
+ if (rolling) {
+ rolling = false;
+ if (status.enableCreep) // a little hack to temporarely disable light
+ deviceManager.sendMessage(DEVICE_DISPLAY, STATUSINDICATOR, MSG_UPDATE, (void*) "on");
+ }
+ } else {
+ if (speedActual > 1000 && !rolling) {
+ rolling = true;
+ deviceManager.sendMessage(DEVICE_DISPLAY, STATUSINDICATOR, MSG_UPDATE, (void*) "off");
+ }
+ }
}
}
-//If we have an ENABLE input configured, this will set opstation to ENABLE anytime it is true (12v), DISABLED if not.
-void MotorController:: checkEnableInput()
+/*
+ * The sub-classes must use this function to report activity/messages from the controller.
+ * In subsequent calls to checkActivity() it is verified if we ran into a timeout.
+ */
+void MotorController::reportActivity()
{
- uint16_t enableinput=getEnableIn();
- if(enableinput >= 0 && enableinput<4) //Do we even have an enable input configured ie NOT 255.
+ if (!running) //if we're newly running then cancel faults if necessary.
{
- if((getDigital(enableinput))||testenableinput) //If it's ON let's set our opstate to ENABLE
- {
- setOpState(ENABLE);
- statusBitfield2 |=1 << enableinput; //set bit to turn on ENABLE annunciator
- statusBitfield2 |=1 << 18;//set bit to turn on enable input annunciator
- }
- else
- {
- setOpState(DISABLED);//If it's off, lets set DISABLED. These two could just as easily be reversed
- statusBitfield2 &= ~(1 << 18); //clear bit to turn off ENABLE annunciator
- statusBitfield2 &= ~(1 << enableinput);//clear bit to turn off enable input annunciator
- }
+// faultHandler.cancelOngoingFault(getId(), FAULT_MOTORCTRL_COMM);
}
+ ticksNoMessage = 0;
}
-//IF we have a reverse input configured, this will set our selected gear to REVERSE any time the input is true, DRIVE if not
-void MotorController:: checkReverseInput()
+/*
+ * Verify if the controller sends messages, if it is online
+ * Otherwise the controller's status flags "ready" and "running"
+ * are set to false and a fault is raised
+ */
+void MotorController::checkActivity()
{
- uint16_t reverseinput=getReverseIn();
- if(reverseinput >= 0 && reverseinput<4) //If we don't have a Reverse Input, do nothing
- {
- if((getDigital(reverseinput))||testreverseinput)
- {
- setSelectedGear(REVERSE);
- statusBitfield2 |=1 << 16; //set bit to turn on REVERSE annunciator
- statusBitfield2 |=1 << reverseinput;//setbit to Turn on reverse input annunciator
- }
- else
- {
- setSelectedGear(DRIVE); //If it's off, lets set to DRIVE.
- statusBitfield2 &= ~(1 << 16); //clear bit to turn off REVERSE annunciator
- statusBitfield2 &= ~(1 << reverseinput);//clear bit to turn off reverse input annunciator
- }
+ if (ticksNoMessage < 255) { // make sure it doesn't overflow
+ ticksNoMessage++;
+ }
+ // We haven't received frames from the controller for a defined number of ticks
+ // But we're in system state "running", so we've lost communications.
+ if (ticksNoMessage > CFG_MOTORCTRL_MAX_NUM_LOST_MSG && status.getSystemState() == Status::running) {
+ running = false;
+ ready = false;
+// faultHandler.raiseFault(getId(), FAULT_MOTORCTRL_COMM, true);
}
}
+int16_t MotorController::processBrakeHold(MotorControllerConfiguration *config, int16_t throttleLvl, int16_t brakeLvl)
+{
+ if (brakeHoldActive) {
+ if (brakeHoldStart == 0) {
+ if (brakeLvl == 0) { // engage brake hold once the brake is released
+ brakeHoldStart = millis();
+ brakeHoldLevel = 0;
+ logger.debug("brake hold engaged for %dms",
+ CFG_BRAKE_HOLD_MAX_TIME);
+ }
+ } else {
+ // deactivate after 5sec or when accelerator gives more torque or we're rolling forward without motor power
+ if (brakeHoldStart + CFG_BRAKE_HOLD_MAX_TIME < millis() || throttleLvl > brakeHoldLevel || (speedActual > 0 && brakeHoldLevel == 0)) {
+ brakeHoldActive = false;
+ brakeHoldLevel = 0;
+ brakeHoldStart = 0;
+ throttleLvl = 0;
+ slewTimestamp = millis(); // this should re-activate slew --> slowly reduce to 0 torque
+ logger.debug("brake hold deactivated");
+ } else {
+ uint16_t delta = abs(speedActual) * 2 / config->brakeHoldForceCoefficient + 1; // make sure it's always bigger than 0
+ if (speedActual < 0 && brakeHoldLevel < config->brakeHold * 10) {
+ brakeHoldLevel += delta;
+ }
+ if (speedActual >= 0 && brakeHoldLevel > 0) {
+ brakeHoldLevel -= (delta * 2); // decrease faster to limit oscillation
+ }
-
-bool MotorController::isRunning() {
- return running;
+ brakeHoldLevel = constrain(brakeHoldLevel, 0, config->brakeHold * 10); // it might have overshot above
+ throttleLvl = brakeHoldLevel;
+ }
+ }
+ } else {
+ if (brakeLvl < 0 && speedActual == 0) { // init brake hold at stand-still when brake is pressed
+ brakeHoldActive = true;
+ brakeHoldStart = 0;
+ logger.debug("brake hold activated");
+ }
+ }
+ return throttleLvl;
}
-bool MotorController::isFaulted() {
- return faulted;
-}
+/**
+ * /brief In case ABS is active, apply no power to wheels to prevent loss of control through regen forces. If gear shift support is enabled, additionally
+ * the motor will be spun up/down to the next
+ */
+void MotorController::processGearChange()
+{
+ if (systemIO.isGearChangeActive()) {
+ throttleLevel = 0;
-bool MotorController::isWarning() {
- return warning;
+ if (gearChangeTimestamp == 0) {
+ logger.debug("Starting gear change cycle");
+ gearChangeTimestamp = millis();
+ cruiseControlDisengage();
+ return;
+ }
+
+ //TODO move values to eeprom parameters
+ uint32_t duration = millis() - gearChangeTimestamp;
+ if (duration > 750 && duration < 1250 && speedActual > 100) {
+ speedRequested = 2500; //TODO calculate correct speed according to vehicle speed and estimated gear change
+ logger.debug("Adjusting motor speed to %drpm", speedRequested);
+
+ if (speedActual > speedRequested) {
+ throttleLevel = -150; // -10% throttle to slow down motor
+ } else {
+ throttleLevel = 150; // 10% throttle to accelerate motor
+ }
+ return;
+ }
+ } else {
+ if (gearChangeTimestamp > 0) {
+ logger.debug("Gear change cycle finished");
+ gearChangeTimestamp = 0;
+ }
+ }
}
+/**
+ * /brief Check if the battery temperatures are below the minimum temperature (configured in charger) in which case no regen should be applied.
+ *
+ * @return true if it's ok to apply regen, false if no regen must be applied
+ */
+bool MotorController::checkBatteryTemperatureForRegen()
+{
+ int16_t lowestBatteryTemperature = status.getLowestBatteryTemperature();
+
+ if (lowestBatteryTemperature != CFG_NO_TEMPERATURE_DATA && (lowestBatteryTemperature * 10) < minimumBatteryTemperature) {
+ status.enableRegen = false;
+ logger.info("No regenerative braking due to low battery temperature! (%f < %f)", lowestBatteryTemperature / 10.0f,
+ minimumBatteryTemperature / 10.0f);
+ return false;
+ }
-DeviceType MotorController::getType() {
- return (DEVICE_MOTORCTRL);
+ return true;
}
-void MotorController::setOpState(OperationState op) {
- operationState = op;
+
+/*
+ * From the throttle and brake level, calculate the requested torque and speed.
+ * Depending on power mode, the throttle dependent value is torque or speed. The other
+ * value is locked to the configured maximum value.
+ */
+void MotorController::processThrottleLevel()
+{
+ MotorControllerConfiguration *config = (MotorControllerConfiguration*) getConfiguration();
+ SystemIOConfiguration *sysConfig = systemIO.getConfiguration();
+ Throttle *accelerator = deviceManager.getAccelerator();
+ Throttle *brake = deviceManager.getBrake();
+
+ throttleLevel = 0; //force to zero in case not in operational condition or no throttle is enabled
+ speedRequested = 0;
+ if (powerOn && ready) {
+ if (accelerator && !accelerator->isFaulted()) {
+ throttleLevel = accelerator->getLevel();
+ }
+ if (cruiseControlEnabled && cruisePid != NULL && (cruiseThrottle - 1000) > throttleLevel) {
+ throttleLevel = round(cruiseThrottle) - 1000;
+ }
+ if (brake && !brake->isFaulted() && brake->getLevel() < 0) { // if the brake has been pressed it overrides the accelerator
+ throttleLevel = brake->getLevel();
+ cruiseControlDisengage();
+ }
+ if (brake && config->brakeHold > 0) { // check if brake hold should be applied
+ throttleLevel = processBrakeHold(config, throttleLevel, brake->getLevel());
+ }
+ if (throttleLevel < 0 && (!status.enableRegen || !checkBatteryTemperatureForRegen())) { // do not apply regen if the batteries are too cold
+ throttleLevel = 0;
+ }
+ if (config->powerMode == modeSpeed) {
+ speedRequested = throttleLevel * config->speedMax / 1000;
+ torqueRequested = config->torqueMax;
+ } else { // torque mode
+ speedRequested = config->speedMax;
+ if (sysConfig->gearChangeInput != CFG_OUTPUT_NONE) {
+ processGearChange(); // will adjust the speedRequested and throttleLevel
+ }
+ int32_t torqueTarget = throttleLevel * config->torqueMax / 1000;
+ uint16_t slewRate = (torqueTarget > 0 || torqueRequested > 0 ? config->slewRateMotor : config->slewRateRegen);
+
+ if (slewRate == 0 || brakeHoldActive) {
+ torqueRequested = torqueTarget;
+ } else { // calc slew part and add/subtract from torqueRequested
+ uint32_t currentTimestamp = millis();
+ uint16_t slewPart = abs(torqueTarget - torqueRequested) * slewRate / 1000 * (currentTimestamp - slewTimestamp) / 1000;
+
+ // if we're we're reversing torque, reduce the slew part in the 0 area to make transitions between positive and negative torque smoother
+ if ((torqueActual * torqueRequested < 0) && abs(torqueRequested) < 150) {
+ slewPart /= 10; //TODO make configurable
+ }
+ if (slewPart == 0 && torqueRequested != torqueTarget) {
+ slewPart = 1;
+ }
+ if (torqueTarget < torqueRequested) {
+ torqueRequested = max(torqueRequested - slewPart, torqueTarget);
+ } else {
+ torqueRequested = min(torqueRequested + slewPart, torqueTarget);
+ }
+ slewTimestamp = currentTimestamp;
+ }
+ }
+ } else {
+ torqueRequested = 0;
+ }
+
+ if (systemIO.isABSActive()) {
+ torqueRequested = 0;
+ logger.warn("ABS active !!");
+ }
}
-MotorController::OperationState MotorController::getOpState() {
- return operationState;
+void MotorController::updateGear()
+{
+ if (powerOn && running) {
+ gear = (systemIO.isReverseSignalPresent() ? GEAR_REVERSE : GEAR_DRIVE);
+ } else {
+ gear = GEAR_NEUTRAL; // stay in neutral until the controller reports that it's running
+ }
}
-MotorController::PowerMode MotorController::getPowerMode() {
- return powerMode;
+
+void MotorController::cruiseControlToggle()
+{
+ if (cruisePid == NULL && speedActual > 1) {
+ MotorControllerConfiguration *config = (MotorControllerConfiguration*) getConfiguration();
+
+ //TODO add implementation for vehicleSpeed (config->cruiseUserpm)
+ cruiseSpeedTarget = speedActual;
+ cruiseSpeedActual = speedActual;
+ for (uint8_t i = 0; i < CFG_CRUISE_SPEED_BUFFER_SIZE; i++) { // pre-fill speed averaging buffer
+ cruiseSpeedBuffer[i] = speedActual;
+ }
+ cruiseThrottle = throttleLevel + 1000.0f; // because PID can't handle negative numbers, cruiseThrottle is offset by +1000 (0-2000)
+
+ logger.debug("Setting cruise control speed to %frpm", cruiseSpeedTarget);
+
+ cruisePid = new PID(&cruiseSpeedActual, &cruiseThrottle, &cruiseSpeedTarget, config->cruiseKp, config->cruiseKi, config->cruiseKd, DIRECT);
+ cruisePid->SetOutputLimits(0, 2000);
+
+ uint32_t interval = tickHandler.getInterval(this);
+ if (interval != 0) {
+ cruisePid->SetSampleTime(interval / 1000);
+ }
+ cruisePid->SetMode(AUTOMATIC);
+ cruiseControlEnabled = true;
+ } else {
+ cruiseControlDisengage();
+ }
}
-void MotorController::setPowerMode(PowerMode mode) {
- powerMode = mode;
+void MotorController::cruiseControlAdjust(int16_t speedDelta)
+{
+ if (!cruiseControlEnabled) {
+ return;
+ }
+ if (cruisePid == NULL) {
+ cruiseControlToggle();
+ }
+ cruiseSpeedTarget += speedDelta;
+ cruiseSpeedLast = cruiseSpeedTarget;
}
+void MotorController::cruiseControlSetSpeed(int16_t speedTarget)
+{
+ if (!cruiseControlEnabled) {
+ return;
+ }
+ if (cruisePid == NULL) {
+ cruiseControlToggle();
+ }
+ cruiseSpeedTarget = speedTarget;
+ cruiseSpeedLast = cruiseSpeedTarget;
+}
+void MotorController::cruiseControlDisengage()
+{
+ if (cruisePid == NULL)
+ return;
-uint32_t MotorController::getStatusBitfield1() {
- return statusBitfield1;
+ logger.debug("Cruise control disengaged");
+ cruisePid = NULL;
+ cruiseSpeedActual = 0;
+ cruiseSpeedTarget = 0;
+ cruiseThrottle = 1000;
}
-uint32_t MotorController::getStatusBitfield2() {
- return statusBitfield2;
-}
+void MotorController::handleCruiseControlButton(CruiseControlButton button)
+{
+ if (button == cruiseLastButton) { // debounce - except for long press of plus/minus
+ if (button != PLUS && button != MINUS)
+ return;
+ } else { // remember time button was pressed
+ if (button != NONE)
+ cruiseButtonPressed = millis();
+ }
-uint32_t MotorController::getStatusBitfield3() {
- return statusBitfield3;
+ MotorControllerConfiguration *config = (MotorControllerConfiguration*) getConfiguration();
+
+ switch (button) {
+ case TOGGLE:
+ if (cruiseControlEnabled) {
+ cruiseControlDisengage();
+ }
+ cruiseControlEnabled = !cruiseControlEnabled;
+ break;
+ case RECALL:
+ if (cruiseSpeedLast > 0) {
+ cruiseControlSetSpeed(cruiseSpeedLast);
+ logger.debug("Resuming cruise control, speed: %d", getCruiseControlSpeed());
+ }
+ break;
+ case PLUS:
+ if (cruiseButtonPressed + CFG_CRUISE_BUTTON_LONG_PRESS < millis()) { // long press -> increase target steadily
+ cruiseControlSetSpeed(speedActual + config->cruiseLongPressDelta);
+ }
+ break;
+ case MINUS:
+ if (cruiseButtonPressed + CFG_CRUISE_BUTTON_LONG_PRESS < millis()) { // long press -> decrease target steadily
+ cruiseControlSetSpeed(speedActual - config->cruiseLongPressDelta);
+ }
+ break;
+ case DISENGAGE:
+ cruiseControlDisengage();
+ break;
+ case NONE:
+ if (cruiseLastButton == PLUS || cruiseLastButton == MINUS) {
+ if (cruiseButtonPressed + CFG_CRUISE_BUTTON_LONG_PRESS < millis() || cruisePid == NULL) {
+ // long press -> set target to current speed
+ cruiseControlSetSpeed(speedActual);
+ } else {
+ // short press and cc already active -> increase/decrease by step
+ cruiseControlAdjust(config->cruiseStepDelta * (cruiseLastButton == PLUS ? 1 : -1));
+ }
+ cruiseButtonPressed = 0;
+ }
+ break;
+ }
+ cruiseLastButton = button;
}
-uint32_t MotorController::getStatusBitfield4() {
- return statusBitfield4;
-}
+void MotorController::handleTick()
+{
+ checkActivity();
+
+ if (cruisePid != NULL) {
+ //TODO add implementation for vehicleSpeed (config->cruiseUserpm)
+ cruiseSpeedBuffer[cruiseSpeedBufferPtr++] = speedActual;
+ if (cruiseSpeedBufferPtr >= CFG_CRUISE_SPEED_BUFFER_SIZE) {
+ cruiseSpeedBufferPtr = 0;
+ }
+ cruiseSpeedSum = 0;
+ for (uint8_t i = 0; i < CFG_CRUISE_SPEED_BUFFER_SIZE; i++) {
+ cruiseSpeedSum += cruiseSpeedBuffer[i];
+ }
+ cruiseSpeedActual = cruiseSpeedSum / CFG_CRUISE_SPEED_BUFFER_SIZE;
+ cruisePid->Compute(); // updates torque
+ }
-int8_t MotorController::getCoolFan() {
- MotorControllerConfiguration *config = (MotorControllerConfiguration *)getConfiguration();
- return config->coolFan;
-}
-int8_t MotorController::getCoolOn() {
- MotorControllerConfiguration *config = (MotorControllerConfiguration *)getConfiguration();
- return config->coolOn;
-}
+ processThrottleLevel();
+ updateGear();
-int8_t MotorController::getCoolOff() {
- MotorControllerConfiguration *config = (MotorControllerConfiguration *)getConfiguration();
- return config->coolOff;
-}
-int8_t MotorController::getBrakeLight() {
- MotorControllerConfiguration *config = (MotorControllerConfiguration *)getConfiguration();
- return config->brakeLight;
-}
-int8_t MotorController::getRevLight() {
- MotorControllerConfiguration *config = (MotorControllerConfiguration *)getConfiguration();
- return config->revLight;
-}
-int8_t MotorController::getEnableIn() {
- MotorControllerConfiguration *config = (MotorControllerConfiguration *)getConfiguration();
- return config->enableIn;
-}
-int8_t MotorController::getReverseIn() {
- MotorControllerConfiguration *config = (MotorControllerConfiguration *)getConfiguration();
- return config->reverseIn;
+ updateStatusIndicator();
}
-int16_t MotorController::getprechargeR() {
- MotorControllerConfiguration *config = (MotorControllerConfiguration *)getConfiguration();
- return config->prechargeR;
+void MotorController::handleCanFrame(CAN_FRAME *frame)
+{
}
+/**
+ * act on messages the super-class does not react upon, like state change
+ * to ready or running which should enable/disable the power-stage of the controller
+ */
+void MotorController::handleStateChange(Status::SystemState oldState, Status::SystemState newState)
+{
+ Device::handleStateChange(oldState, newState);
-int8_t MotorController::getprechargeRelay() {
- MotorControllerConfiguration *config = (MotorControllerConfiguration *)getConfiguration();
- return config->prechargeRelay;
-}
+ powerOn = (newState == Status::running ? true : false);
+ if (!powerOn) {
+ throttleLevel = 0;
+ gear = GEAR_NEUTRAL;
+ }
-int8_t MotorController::getmainContactorRelay() {
- MotorControllerConfiguration *config = (MotorControllerConfiguration *)getConfiguration();
- return config->mainContactorRelay;
-}
+ systemIO.setEnableMotor(newState == Status::ready || newState == Status::running);
-int16_t MotorController::getThrottle() {
- return throttleRequested;
+ if (newState == Status::ready) { // at this time also the charger config should be loaded
+ // get the minimum temperature from the charger
+ Charger *charger = deviceManager.getCharger();
+ if (charger) {
+ ChargerConfiguration *config = (ChargerConfiguration*) charger->getConfiguration();
+ if (config) {
+ minimumBatteryTemperature = config->minimumTemperature;
+ }
+ }
+ }
}
-int16_t MotorController::getSpeedRequested() {
- return speedRequested;
-}
+void MotorController::setup()
+{
+ Device::setup();
-int16_t MotorController::getSpeedActual() {
- return speedActual;
+ rolling = false;
+ slewTimestamp = millis();
}
-int16_t MotorController::getTorqueRequested() {
- return torqueRequested;
-}
+/**
+ * Tear down the controller in a safe way.
+ */
+void MotorController::tearDown()
+{
+ Device::tearDown();
-int16_t MotorController::getTorqueActual() {
- return torqueActual;
+ throttleLevel = 0;
+ gear = GEAR_NEUTRAL;
}
- MotorController::Gears MotorController::getSelectedGear() {
- return selectedGear;
-}
-void MotorController::setSelectedGear(Gears gear) {
- selectedGear=gear;
+int16_t MotorController::getThrottleLevel()
+{
+ return throttleLevel;
}
-
-int16_t MotorController::getTorqueAvailable() {
- return torqueAvailable;
+int16_t MotorController::getSpeedRequested()
+{
+ return speedRequested;
}
-uint16_t MotorController::getDcVoltage() {
- return dcVoltage;
+int16_t MotorController::getSpeedActual()
+{
+ return speedActual;
}
-int16_t MotorController::getDcCurrent() {
- return dcCurrent;
+int16_t MotorController::getTorqueRequested()
+{
+ return torqueRequested;
}
-uint16_t MotorController::getAcCurrent() {
- return acCurrent;
+int16_t MotorController::getTorqueActual()
+{
+ return torqueActual;
}
-int16_t MotorController::getnominalVolt() {
- return nominalVolts;
+MotorController::Gears MotorController::getGear()
+{
+ return gear;
}
-uint32_t MotorController::getKiloWattHours() {
- return kiloWattHours;
+int16_t MotorController::getTorqueAvailable()
+{
+ return torqueAvailable;
}
-int16_t MotorController::getMechanicalPower() {
- return mechanicalPower;
+uint16_t MotorController::getDcVoltage()
+{
+ return dcVoltage;
}
-int16_t MotorController::getTemperatureMotor() {
- return temperatureMotor;
+int16_t MotorController::getDcCurrent()
+{
+ return dcCurrent;
}
-int16_t MotorController::getTemperatureInverter() {
- return temperatureInverter;
+uint16_t MotorController::getAcCurrent()
+{
+ return acCurrent;
}
-int16_t MotorController::getTemperatureSystem() {
- return temperatureSystem;
+/**
+ * Return mechanical power in Watts
+ */
+int16_t MotorController::getMechanicalPower()
+{
+ return dcVoltage * dcCurrent / 100;
}
+int16_t MotorController::getTemperatureMotor()
+{
+ return temperatureMotor;
+}
+int16_t MotorController::getTemperatureController()
+{
+ return temperatureController;
+}
-uint32_t MotorController::getTickInterval() {
- return CFG_TICK_INTERVAL_MOTOR_CONTROLLER;
+bool MotorController::isCruiseControlEnabled()
+{
+ return cruiseControlEnabled;
}
-bool MotorController::isReady() {
- return false;
+int16_t MotorController::getCruiseControlSpeed()
+{
+ return cruiseSpeedTarget;
}
-void MotorController::loadConfiguration() {
- MotorControllerConfiguration *config = (MotorControllerConfiguration *)getConfiguration();
+void MotorController::loadConfiguration()
+{
+ MotorControllerConfiguration *config = (MotorControllerConfiguration*) getConfiguration();
- Device::loadConfiguration(); // call parent
+ Device::loadConfiguration(); // call parent
+ logger.info(this, "Motor controller configuration:");
#ifdef USE_HARD_CODED
- if (false) {
+
+ if (false) {
#else
- if (prefsHandler->checksumValid()) { //checksum is good, read in the values stored in EEPROM
+
+ if (prefsHandler->checksumValid()) { //checksum is good, read in the values stored in EEPROM
#endif
- prefsHandler->read(EEMC_MAX_RPM, &config->speedMax);
- prefsHandler->read(EEMC_MAX_TORQUE, &config->torqueMax);
- prefsHandler->read(EEMC_RPM_SLEW_RATE, &config->speedSlewRate);
- prefsHandler->read(EEMC_TORQUE_SLEW_RATE, &config->torqueSlewRate);
- prefsHandler->read(EEMC_REVERSE_LIMIT, &config->reversePercent);
- prefsHandler->read(EEMC_KILOWATTHRS, &config->kilowattHrs);
- prefsHandler->read(EEMC_PRECHARGE_R, &config->prechargeR);
- prefsHandler->read(EEMC_NOMINAL_V, &config->nominalVolt);
- prefsHandler->read(EEMC_PRECHARGE_RELAY, &config->prechargeRelay);
- prefsHandler->read(EEMC_CONTACTOR_RELAY, &config->mainContactorRelay);
- prefsHandler->read(EEMC_COOL_FAN, &config->coolFan);
- prefsHandler->read(EEMC_COOL_ON, &config->coolOn);
- prefsHandler->read(EEMC_COOL_OFF, &config->coolOff);
- prefsHandler->read(EEMC_BRAKE_LIGHT, &config->brakeLight);
- prefsHandler->read(EEMC_REV_LIGHT, &config->revLight);
- prefsHandler->read(EEMC_ENABLE_IN, &config->enableIn);
- prefsHandler->read(EEMC_REVERSE_IN, &config->reverseIn);
-
- }
- else { //checksum invalid. Reinitialize values and store to EEPROM
- config->speedMax = MaxRPMValue;
- config->torqueMax = MaxTorqueValue;
- config->speedSlewRate = RPMSlewRateValue;
- config->torqueSlewRate = TorqueSlewRateValue;
- config->reversePercent = ReversePercent;
- config->kilowattHrs = KilowattHrs;
- config->prechargeR = PrechargeR;
- config->nominalVolt = NominalVolt;
- config->prechargeRelay = PrechargeRelay;
- config->mainContactorRelay = MainContactorRelay;
- config->coolFan = CoolFan;
- config->coolOn = CoolOn;
- config->coolOff = CoolOff;
- config->brakeLight = BrakeLight;
- config->revLight = RevLight;
- config->enableIn = EnableIn;
- config->reverseIn = ReverseIn;
-
- }
- //DeviceManager::getInstance()->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_CONFIG_CHANGE, NULL);
-
- Logger::info("MaxTorque: %i MaxRPM: %i", config->torqueMax, config->speedMax);
-}
-
-void MotorController::saveConfiguration() {
- MotorControllerConfiguration *config = (MotorControllerConfiguration *)getConfiguration();
-
- Device::saveConfiguration(); // call parent
-
- prefsHandler->write(EEMC_MAX_RPM, config->speedMax);
- prefsHandler->write(EEMC_MAX_TORQUE, config->torqueMax);
- prefsHandler->write(EEMC_RPM_SLEW_RATE, config->speedSlewRate);
- prefsHandler->write(EEMC_TORQUE_SLEW_RATE, config->torqueSlewRate);
- prefsHandler->write(EEMC_REVERSE_LIMIT, config->reversePercent);
- prefsHandler->write(EEMC_KILOWATTHRS, config->kilowattHrs);
- prefsHandler->write(EEMC_PRECHARGE_R, config->prechargeR);
- prefsHandler->write(EEMC_NOMINAL_V, config->nominalVolt);
- prefsHandler->write(EEMC_CONTACTOR_RELAY, config->mainContactorRelay);
- prefsHandler->write(EEMC_PRECHARGE_RELAY, config->prechargeRelay);
- prefsHandler->write(EEMC_COOL_FAN, config->coolFan);
- prefsHandler->write(EEMC_COOL_ON, config->coolOn);
- prefsHandler->write(EEMC_COOL_OFF, config->coolOff);
- prefsHandler->write(EEMC_BRAKE_LIGHT, config->brakeLight);
- prefsHandler->write(EEMC_REV_LIGHT, config->revLight);
- prefsHandler->write(EEMC_ENABLE_IN, config->enableIn);
- prefsHandler->write(EEMC_REVERSE_IN, config->reverseIn);
-
-
- prefsHandler->saveChecksum();
- loadConfiguration();
+ uint8_t temp;
+ uint16_t value;
+ prefsHandler->read(EEMC_INVERT_DIRECTION, &temp);
+ config->invertDirection = temp;
+ prefsHandler->read(EEMC_MAX_RPM, &config->speedMax);
+ prefsHandler->read(EEMC_MAX_TORQUE, &config->torqueMax);
+ prefsHandler->read(EEMC_SLEW_RATE_REGEN, &config->slewRateRegen);
+ prefsHandler->read(EEMC_SLEW_RATE_MOTOR, &config->slewRateMotor);
+ prefsHandler->read(EEMC_MAX_MECH_POWER_MOTOR, &config->maxMechanicalPowerMotor);
+ prefsHandler->read(EEMC_MAX_MECH_POWER_REGEN, &config->maxMechanicalPowerRegen);
+ prefsHandler->read(EEMC_REVERSE_LIMIT, &config->reversePercent);
+ prefsHandler->read(EEMC_NOMINAL_V, &config->nominalVolt);
+ prefsHandler->read(EEMC_POWER_MODE, (uint8_t*) &config->powerMode);
+ prefsHandler->read(EEMC_CREEP_LEVEL, &config->creepLevel);
+ prefsHandler->read(EEMC_CREEP_SPEED, &config->creepSpeed);
+ prefsHandler->read(EEMC_BRAKE_HOLD, &config->brakeHold);
+ prefsHandler->read(EEMC_BRAKE_HOLD_COEFF, &config->brakeHoldForceCoefficient);
+ prefsHandler->read(EEMC_CRUISE_KP, &value);
+ config->cruiseKp = value / 1000.0f;
+ prefsHandler->read(EEMC_CRUISE_KI, &value);
+ config->cruiseKi = value / 1000.0f;
+ prefsHandler->read(EEMC_CRUISE_KD, &value);
+ config->cruiseKd = value / 1000.0f;
+ prefsHandler->read(EEMC_CRUISE_LONG_PRESS_DELTA, &config->cruiseLongPressDelta);
+ prefsHandler->read(EEMC_CRUISE_STEP_DELTA, &config->cruiseStepDelta);
+ prefsHandler->read(EEMC_CRUISE_USE_RPM, &temp);
+ config->cruiseUseRpm = temp;
+ } else { //checksum invalid. Reinitialize values and store to EEPROM
+ config->invertDirection = false;
+ config->speedMax = 6000;
+ config->torqueMax = 3000;
+ config->slewRateRegen = 0;
+ config->slewRateMotor = 0;
+ config->maxMechanicalPowerMotor = 2000;
+ config->maxMechanicalPowerRegen = 400;
+ config->reversePercent = 50;
+ config->nominalVolt = 3300;
+ config->powerMode = modeTorque;
+ config->creepLevel = 0;
+ config->creepSpeed = 0;
+ config->brakeHold = 0;
+ config->cruiseKp = .5f;
+ config->cruiseKi = .2f;
+ config->cruiseKd = .02f;
+ config->cruiseLongPressDelta = 500;
+ config->cruiseStepDelta = 300;
+ config->cruiseUseRpm = true;
+ }
+
+ //TODO move to eeprom config?
+ config->speedSet[0] = 1800;
+ config->speedSet[1] = 3035;
+ config->speedSet[2] = 4800;
+ config->speedSet[3] = 3050;
+ config->speedSet[4] = 3700;
+ config->speedSet[5] = 0;
+ config->speedSet[6] = 0;
+ config->speedSet[7] = 0;
+
+ logger.info(this, "Power mode: %s, Max torque: %i", (config->powerMode == modeTorque ? "torque" : "speed"), config->torqueMax);
+ logger.info(this, "Max RPM: %i, Slew rate: %i motor, %i regen", config->speedMax, config->slewRateMotor, config->slewRateRegen);
+ logger.info(this, "Max mech power motor: %fkW, Max mech power regen: %fkW", config->maxMechanicalPowerMotor / 10.0f,
+ config->maxMechanicalPowerRegen / 10.0f);
+ logger.info(this, "Creep level: %i, Creep speed: %i, Brake Hold: %d", config->creepLevel, config->creepSpeed,
+ config->brakeHold);
+ logger.info(this, "Cruise Kp: %f, Ki: %f, Kd: %f, long delta: %d, step delta: %d, rpm: %d", config->cruiseKp, config->cruiseKi, config->cruiseKd,
+ config->cruiseLongPressDelta, config->cruiseStepDelta, config->cruiseUseRpm);
+}
+
+void MotorController::saveConfiguration()
+{
+ MotorControllerConfiguration *config = (MotorControllerConfiguration*) getConfiguration();
+
+ Device::saveConfiguration(); // call parent
+
+ prefsHandler->write(EEMC_INVERT_DIRECTION, (uint8_t) (config->invertDirection ? 1 : 0));
+ prefsHandler->write(EEMC_MAX_RPM, config->speedMax);
+ prefsHandler->write(EEMC_MAX_TORQUE, config->torqueMax);
+ prefsHandler->write(EEMC_SLEW_RATE_REGEN, config->slewRateRegen);
+ prefsHandler->write(EEMC_SLEW_RATE_MOTOR, config->slewRateMotor);
+ prefsHandler->write(EEMC_MAX_MECH_POWER_MOTOR, config->maxMechanicalPowerMotor);
+ prefsHandler->write(EEMC_MAX_MECH_POWER_REGEN, config->maxMechanicalPowerRegen);
+ prefsHandler->write(EEMC_REVERSE_LIMIT, config->reversePercent);
+ prefsHandler->write(EEMC_NOMINAL_V, config->nominalVolt);
+ prefsHandler->write(EEMC_POWER_MODE, (uint8_t) config->powerMode);
+ prefsHandler->write(EEMC_CREEP_LEVEL, config->creepLevel);
+ prefsHandler->write(EEMC_CREEP_SPEED, config->creepSpeed);
+ prefsHandler->write(EEMC_BRAKE_HOLD, config->brakeHold);
+ prefsHandler->write(EEMC_BRAKE_HOLD_COEFF, config->brakeHoldForceCoefficient);
+ prefsHandler->write(EEMC_CRUISE_KP, (uint16_t) (config->cruiseKp * 1000));
+ prefsHandler->write(EEMC_CRUISE_KI, (uint16_t) (config->cruiseKi * 1000));
+ prefsHandler->write(EEMC_CRUISE_KD, (uint16_t) (config->cruiseKd * 1000));
+ prefsHandler->write(EEMC_CRUISE_LONG_PRESS_DELTA, config->cruiseLongPressDelta);
+ prefsHandler->write(EEMC_CRUISE_STEP_DELTA, config->cruiseStepDelta);
+ prefsHandler->write(EEMC_CRUISE_USE_RPM, (uint8_t) (config->cruiseUseRpm ? 1 : 0));
+
+ prefsHandler->saveChecksum();
}
diff --git a/MotorController.h b/MotorController.h
index 33901b9..dc7674f 100644
--- a/MotorController.h
+++ b/MotorController.h
@@ -33,177 +33,139 @@
#include "config.h"
#include "Device.h"
#include "Throttle.h"
+#include "CanHandler.h"
#include "DeviceManager.h"
-#include "sys_io.h"
+#include "FaultHandler.h"
+#include "PID_v1.h"
+
#define MOTORCTL_INPUT_DRIVE_EN 3
#define MOTORCTL_INPUT_FORWARD 4
#define MOTORCTL_INPUT_REVERSE 5
#define MOTORCTL_INPUT_LIMP 6
-class MotorControllerConfiguration : public DeviceConfiguration {
-public:
- uint16_t speedMax; // in rpm
- uint16_t torqueMax; // maximum torque in 0.1 Nm
- uint16_t torqueSlewRate; // for torque mode only: slew rate of torque value, 0=disabled, in 0.1Nm/sec
- uint16_t speedSlewRate; // for speed mode only: slew rate of speed value, 0=disabled, in rpm/sec
- uint8_t reversePercent;
- uint16_t kilowattHrs;
- uint16_t prechargeR; //resistance of precharge resistor in tenths of ohm
- uint16_t nominalVolt; //nominal pack voltage in tenths of a volt
- uint8_t prechargeRelay; //# of output to use for this relay or 255 if there is no relay
- uint8_t mainContactorRelay; //# of output to use for this relay or 255 if there is no relay
- uint8_t coolFan;
- uint8_t coolOn;
- uint8_t coolOff;
- uint8_t brakeLight;
- uint8_t revLight;
- uint8_t enableIn;
- uint8_t reverseIn;
-
+class CanHandler;
+
+enum PowerMode {
+ modeTorque = 0,
+ modeSpeed = 1
};
-class MotorController: public Device {
+class MotorControllerConfiguration : public DeviceConfiguration
+{
+public:
+ bool invertDirection; // should an AC motor run in reverse mode? (e.g. negative speed for forward motion)
+ uint16_t speedMax; // in rpm
+ uint16_t torqueMax; // maximum torque in 0.1 Nm
+ uint16_t slewRateMotor; // slew rate of torque/speed value for motoring in 0.1 percent/sec
+ uint16_t slewRateRegen; // slew rate of torque/speed value for regen in 0.1 percent/sec
+ uint16_t maxMechanicalPowerMotor; // maximal mechanical power of motor in 100W steps
+ uint16_t maxMechanicalPowerRegen; // maximal mechanical power of regen in 100W steps
+ uint8_t reversePercent;
+ uint16_t nominalVolt; //nominal pack voltage in tenths of a volt
+ PowerMode powerMode;
+ uint8_t creepLevel; // percentage of torque used for creep function (imitate creep of automatic transmission, set 0 to disable)
+ uint16_t creepSpeed; // max speed for creep
+ uint8_t brakeHold; // percentage of max torque to achieve brake hold (0 = off)
+ uint8_t brakeHoldForceCoefficient; // quotient by which the negative rpm is divided to get the force increase/decrease during brake hold (must NOT be 0!)
+ double cruiseKp, cruiseKi, cruiseKd; // PID parameter for cruise control
+ uint16_t cruiseLongPressDelta; // delta in rpm/kph to increase/decrease target speed for cc during long button press
+ uint16_t cruiseStepDelta; // delta in rpm/kph to increase/decrease target speed for cc at short button press
+ bool cruiseUseRpm; // true = use rpm to control cruise control, false = use vehicle speed instead
+ uint16_t speedSet[CFG_CRUISE_SIZE_SPEED_SET]; // speed sets for dashboard buttons
+};
+class MotorController: public Device, public CanObserver
+{
public:
- enum Gears {
- NEUTRAL = 0,
- DRIVE = 1,
- REVERSE = 2,
- ERROR = 3,
- };
-
- enum PowerMode {
- modeTorque,
- modeSpeed
- };
-
- enum OperationState {
- DISABLED = 0,
- STANDBY = 1,
- ENABLE = 2,
- POWERDOWN = 3
- };
+ enum Gears {
+ GEAR_NEUTRAL = 0,
+ GEAR_DRIVE = 1,
+ GEAR_REVERSE = 2,
+ GEAR_ERROR = 3
+ };
+
+ enum CruiseControlButton {
+ NONE, TOGGLE, RECALL, PLUS, MINUS, DISENGAGE
+ };
MotorController();
- DeviceType getType();
+ DeviceType getType();
void setup();
+ void tearDown();
void handleTick();
- uint32_t getTickInterval();
-
- void loadConfiguration();
- void saveConfiguration();
-
- void coolingcheck();
- void checkBrakeLight();
- void checkReverseLight();
- void checkEnableInput();
- void checkReverseInput();
- void checkPrecharge();
-
- void brakecheck();
- bool isReady();
- bool isRunning();
- bool isFaulted();
- bool isWarning();
-
-uint32_t getStatusBitfield1();
-uint32_t getStatusBitfield2();
-uint32_t getStatusBitfield3();
-uint32_t getStatusBitfield4();
-
-uint32_t statusBitfield1; // bitfield variable for use of the specific implementation
-uint32_t statusBitfield2;
-uint32_t statusBitfield3;
-uint32_t statusBitfield4;
-
-
-
-
- void setPowerMode(PowerMode mode);
- PowerMode getPowerMode();
- void setOpState(OperationState op) ;
- OperationState getOpState() ;
- void setSelectedGear(Gears gear);
- Gears getSelectedGear();
-
- int16_t getThrottle();
- int8_t getCoolFan();
- int8_t getCoolOn();
- int8_t getCoolOff();
- int8_t getBrakeLight();
- int8_t getRevLight();
- int8_t getEnableIn();
- int8_t getReverseIn();
- int16_t getselectedGear();
- int16_t getprechargeR();
- int16_t getnominalVolt();
- int8_t getprechargeRelay();
- int8_t getmainContactorRelay();
+ void handleCanFrame(CAN_FRAME *);
+ void handleStateChange(Status::SystemState, Status::SystemState);
+ void cruiseControlToggle();
+ void cruiseControlDisengage();
+ void cruiseControlAdjust(int16_t);
+ void cruiseControlSetSpeed(int16_t);
+ void handleCruiseControlButton(CruiseControlButton);
+ bool isCruiseControlEnabled();
+ int16_t getCruiseControlSpeed();
+
+ void loadConfiguration();
+ void saveConfiguration();
+
+ int16_t getThrottleLevel();
+ Gears getGear();
int16_t getSpeedRequested();
int16_t getSpeedActual();
int16_t getTorqueRequested();
int16_t getTorqueActual();
int16_t getTorqueAvailable();
- int preMillis();
-
- uint16_t getDcVoltage();
- int16_t getDcCurrent();
- uint16_t getAcCurrent();
- uint32_t getKiloWattHours();
- int16_t getMechanicalPower();
- int16_t getTemperatureMotor();
- int16_t getTemperatureInverter();
- int16_t getTemperatureSystem();
-
-
- int milliseconds ;
- int seconds;
- int minutes;
- int hours ;
- int premillis;
-
-
+
+ uint16_t getDcVoltage();
+ int16_t getDcCurrent();
+ uint16_t getAcCurrent();
+ int16_t getMechanicalPower();
+ int16_t getTemperatureMotor();
+ int16_t getTemperatureController();
+ int16_t getNominalVolt();
protected:
- bool ready; // indicates if the controller is ready to enable the power stage
- bool running; // indicates if the power stage of the inverter is operative
- bool faulted; // indicates a error condition is present in the controller
- bool warning; // indicates a warning condition is present in the controller
- bool coolflag;
- bool testenableinput;
- bool testreverseinput;
-
-
- Gears selectedGear;
-
- PowerMode powerMode;
- OperationState operationState; //the op state we want
-
- int16_t throttleRequested; // -1000 to 1000 (per mille of throttle level)
- int16_t speedRequested; // in rpm
- int16_t speedActual; // in rpm
- int16_t torqueRequested; // in 0.1 Nm
- int16_t torqueActual; // in 0.1 Nm
- int16_t torqueAvailable; // the maximum available torque in 0.1Nm
-
- uint16_t dcVoltage; // DC voltage in 0.1 Volts
- int16_t dcCurrent; // DC current in 0.1 Amps
- uint16_t acCurrent; // AC current in 0.1 Amps
- uint32_t kiloWattHours;
- int16_t mechanicalPower; // mechanical power of the motor 0.1 kW
- int16_t temperatureMotor; // temperature of motor in 0.1 degree C
- int16_t temperatureInverter; // temperature of inverter power stage in 0.1 degree C
- int16_t temperatureSystem; // temperature of controller in 0.1 degree C
-
-
- uint16_t nominalVolts; //nominal pack voltage in 1/10 of a volt
-
- uint16_t prechargeTime; //time in ms that precharge should last
- uint32_t milliStamp; //how long we have precharged so far
- bool donePrecharge; //already completed the precharge cycle?
- bool prelay;
- uint32_t skipcounter;
+ int16_t speedActual; // in rpm
+ int16_t torqueActual; // in 0.1 Nm
+ int16_t torqueAvailable; // the maximum available torque in 0.1Nm
+
+ uint16_t dcVoltage; // DC voltage in 0.1 Volts
+ int16_t dcCurrent; // DC current in 0.1 Amps
+ uint16_t acCurrent; // AC current in 0.1 Amps
+ int16_t temperatureMotor; // temperature of motor in 0.1 degree C
+ int16_t temperatureController; // temperature of controller in 0.1 degree C
+
+ bool rolling; // flag wether to save power consumption to eeprom
+ void reportActivity();
+
+private:
+ int16_t throttleLevel; // -1000 to 1000 (per mille of throttle level)
+ int16_t torqueRequested; // in 0.1 Nm, calculated in MotorController - must not be manipulated by subclasses
+ int16_t speedRequested; // in rpm, calculated in MotorController - must not be manipulated by subclasses
+ uint8_t ticksNoMessage; // counter how many ticks the device went through without any message from the controller
+ uint32_t slewTimestamp; // time stamp of last slew rate calculation
+ int16_t minimumBatteryTemperature; // battery temperature in 0.1 deg Celsius below which no regen will not occur
+ bool brakeHoldActive; // flag to signal if brake hold was activated by a standing car and pressed brake
+ uint32_t brakeHoldStart; // timestamp at which the brake hold was activated
+ int16_t brakeHoldLevel; // current throttle level applied by brake hold (must be signed to prevent overflow!!)
+ uint32_t gearChangeTimestamp;
+ Gears gear;
+ double cruiseSpeedTarget, cruiseSpeedActual, cruiseThrottle; // PID parameters for cruise control, cruiseThrottle is 0-2000 (+1000 offset to throttle because PID can't handle negative values.
+ double cruiseSpeedLast; // the last active cruise control speed (for recall)
+ PID *cruisePid; // PID controller for cruise control
+ int16_t cruiseSpeedBuffer[CFG_CRUISE_SPEED_BUFFER_SIZE]; // buffer to average actual speed measurements and reduce jumps
+ uint8_t cruiseSpeedBufferPtr; // pointer to current speed buffer position
+ uint32_t cruiseSpeedSum; // temp variable to sum up buffered speed
+ bool cruiseControlEnabled; // main switch if cruise control is enabled at all (power switch)
+ CruiseControlButton cruiseLastButton; // which button was last pressed
+ uint32_t cruiseButtonPressed; // timestamp when a cruise control button was pressed
+
+ void updateStatusIndicator();
+ void checkActivity();
+ void processThrottleLevel();
+ void updateGear();
+ int16_t processBrakeHold(MotorControllerConfiguration *config, int16_t throttleLevel, int16_t brakeLevel);
+ void processGearChange();
+ bool checkBatteryTemperatureForRegen();
};
#endif
diff --git a/OBD2Handler.cpp b/OBD2Handler.cpp
index 86bcf54..0087af5 100644
--- a/OBD2Handler.cpp
+++ b/OBD2Handler.cpp
@@ -1,9 +1,9 @@
/*
* OBD2Handler.cpp - A simple utility class that can be used to handle OBDII traffic
- * of any form. It takes pointers to buffers where upwards of 8 characters reside.
+ * of any form. It takes pointers to buffers where upwards of 8 characters reside.
* Doesn't care about how the traffic came out or how it'll go out. That is handled
- * in places like CanPIDListener or ELM327Emu
- *
+ * in places like CanOBD2 or ELM327Emu
+ *
*
Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
@@ -30,195 +30,292 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
#include "OBD2Handler.h"
-OBD2Handler *OBD2Handler::instance = NULL;
-
-OBD2Handler::OBD2Handler() {
-
- motorController = (MotorController*) DeviceManager::getInstance()->getMotorController();
- accelPedal = (Throttle*) DeviceManager::getInstance()->getAccelerator();
- brakePedal = (Throttle*) DeviceManager::getInstance()->getBrake();
- BMS = (BatteryManager*) DeviceManager::getInstance()->getDeviceByType(DEVICE_BMS);
+OBD2Handler::OBD2Handler()
+{
+ motorController = (MotorController*) deviceManager.getMotorController();
+ accelPedal = (Throttle*) deviceManager.getAccelerator();
+ brakePedal = (Throttle*) deviceManager.getBrake();
+ BMS = (BatteryManager*) deviceManager.getDeviceByType(DEVICE_BMS);
}
-OBD2Handler *OBD2Handler::getInstance() {
- if (instance == NULL)
- instance = new OBD2Handler();
- return instance;
+OBD2Handler *OBD2Handler::getInstance()
+{
+ static OBD2Handler *obd2Handler = new OBD2Handler();
+ return obd2Handler;
}
/*
-Public method to process OBD2 requests.
- inData is whatever payload the request might need to have sent - it's OK to be NULL if this is a run of the mill PID request with no payload
- outData should be a preallocated buffer of at least 6 bytes. The format is as follows:
- outData[0] is the length of the data actually returned
- outData[1] is the returned mode (input mode + 0x40)
- there after, the rest of the bytes are the data requested. This should be 1-5 bytes
+Public method to process OBD2 requests.
+ inData is whatever payload the request might need to have sent - it's OK to be NULL if this is a run of the mill PID request with no payload
+ outData should be a preallocated buffer of at least 6 bytes. The format is as follows:
+ outData[0] is the length of the data actually returned
+ outData[1] is the returned mode (input mode + 0x40)
+ there after, the rest of the bytes are the data requested. This should be 1-5 bytes
+
+ SAE standard says that this is the format for SAE requests to us:
+ byte 0 = # of bytes following
+ byte 1 = mode for PID request
+ byte 2 = PID requested
+
+ However, the sky is the limit for non-SAE frames (modes over 0x09)
+ In that case we'll use two bytes for our custom PIDS (sent MSB first like
+ all other PID traffic) MSB = byte 2, LSB = byte 3.
+
+ These are the PIDs I think we should support (mode 1)
+ 0 = lets the other side know which pids we support. A bitfield that runs from MSb of first byte to lsb of last byte (32 bits)
+ 1 = Returns 32 bits but we really can only support the first byte which has bit 7 = Malfunction? Bits 0-6 = # of DTCs
+ 2 = Freeze DTC
+ 4 = Calculated engine load (A * 100 / 255) - Percentage
+ 5 = Engine Coolant Temp (A - 40) = Degrees Centigrade
+ 0x0C = Engine RPM (A * 256 + B) / 4
+ 0x11 = Throttle position (A * 100 / 255) - Percentage
+ 0x1C = Standard supported (We return 1 = OBDII)
+ 0x1F = runtime since engine start (A*256 + B)
+ 0x20 = pids supported (next 32 pids - formatted just like PID 0)
+ 0x21 = Distance traveled with fault light lit (A*256 + B) - In km
+ 0x2F = Fuel level (A * 100 / 255) - Percentage
+ 0x40 = PIDs supported, next 32
+ 0x51 = What type of fuel do we use? (We use 8 = electric, presumably.)
+ 0x60 = PIDs supported, next 32
+ 0x61 = Driver requested torque (A-125) - Percentage
+ 0x62 = Actual Torque delivered (A-125) - Percentage
+ 0x63 = Reference torque for engine - presumably max torque - A*256 + B - Nm
+
+ Mode 3
+ Returns DTC (diag trouble codes) - Three per frame
+ bits 6-7 = DTC first character (00 = P = Powertrain, 01=C=Chassis, 10=B=Body, 11=U=Network)
+ bits 4-5 = Second char (00 = 0, 01 = 1, 10 = 2, 11 = 3)
+ bits 0-3 = third char (stored as normal nibble)
+ Then next byte has two nibbles for the next 2 characters (fourth char = bits 4-7, fifth = 0-3)
+
+ Mode 9 PIDs
+ 0x0 = Mode 9 pids supported (same scheme as mode 1)
+ 0x9 = How long is ECU name returned by 0x0A?
+ 0xA = ASCII string of ECU name. 20 characters are to be returned, I believe 4 at a time
*/
-bool OBD2Handler::processRequest(uint8_t mode, uint8_t pid, char *inData, char *outData) {
- bool ret = false;
- switch (mode) {
- case 1: //show current data
- ret = processShowData(pid, inData, outData);
- outData[1] = mode + 0x40;
- outData[2] = pid;
- break;
- case 2: //show freeze frame data - not sure we'll be supporting this
- break;
- case 3: //show stored diagnostic codes - we can probably map our faults to some existing DTC codes or roll our own
- break;
- case 4: //clear diagnostic trouble codes - If we get this frame we just clear all codes no questions asked.
- break;
- case 6: //test results over CANBus (this replaces mode 5 from non-canbus) - I know nothing of this
- break;
- case 7: //show pending diag codes (current or last driving cycle) - Might just overlap with mode 3
- break;
- case 8: //control operation of on-board systems - this sounds really proprietary and dangerous. Maybe ignore this?
- break;
- case 9: //request vehicle info - We can identify ourselves here but little else
- break;
- case 0x20: //custom PID codes we made up for GEVCU
- break;
- }
- return ret;
+bool OBD2Handler::processRequest(byte *inData, byte *outData)
+{
+ bool ret = false;
+
+ outData[2] = inData[2]; //copy standard PID
+ outData[0] = 2;
+
+ if (inData[1] > 0x50) {
+ outData[3] = inData[3]; //if using proprietary PIDs then copy second byte too
+ outData[0] = 3;
+ }
+
+ uint8_t mode = inData[1];
+ uint16_t pid;
+ if (mode < 10) {
+ pid = inData[2];
+ } else {
+ pid = inData[2] * 256 + inData[3];
+ }
+
+ switch (mode) {
+ case 1: //show current data
+ ret = processShowData(pid, inData, outData);
+ outData[1] = mode + 0x40;
+ outData[2] = pid;
+ break;
+
+ case 2: //show freeze frame data - not sure we'll be supporting this
+ break;
+
+ case 3: //show stored diagnostic codes - we can probably map our faults to some existing DTC codes or roll our own
+ break;
+
+ case 4: //clear diagnostic trouble codes - If we get this frame we just clear all codes no questions asked.
+ break;
+
+ case 6: //test results over CANBus (this replaces mode 5 from non-canbus) - I know nothing of this
+ break;
+
+ case 7: //show pending diag codes (current or last driving cycle) - Might just overlap with mode 3
+ break;
+
+ case 8: //control operation of on-board systems - this sounds really proprietary and dangerous. Maybe ignore this?
+ break;
+
+ case 9: //request vehicle info - We can identify ourselves here but little else
+ break;
+
+ case 0x20: //custom PID codes we made up for GEVCU
+ break;
+ }
+
+ return ret;
}
//Process SAE standard PID requests. Function returns whether it handled the request or not.
-bool OBD2Handler::processShowData(uint8_t pid, char *inData, char *outData) {
- int temp;
-
-
- switch (pid) {
- case 0: //pids 1-0x20 that we support - bitfield
- //returns 4 bytes so immediately indicate that.
- outData[0] = 4;
- outData[3] = 0b11011000; //pids 1 - 8 - starting with pid 1 in the MSB and going from there
- outData[4] = 0b00010000; //pids 9 - 0x10
- outData[5] = 0b10000000; //pids 0x11 - 0x18
- outData[6] = 0b00010011; //pids 0x19 - 0x20
- return true;
- break;
- case 1: //Returns 32 bits but we really can only support the first byte which has bit 7 = Malfunction? Bits 0-6 = # of DTCs
- outData[0] = 4;
- outData[3] = 0; //TODO: We aren't properly keeping track of faults yet but when we do fix this.
- outData[4] = 0; //these next three are really related to ICE diagnostics
- outData[5] = 0; //so ignore them.
- outData[6] = 0;
- return true;
- break;
- case 2: //Freeze DTC
- return false; //don't support freeze framing yet. Might be useful in the future.
- break;
- case 4: //Calculated engine load (A * 100 / 255) - Percentage
- temp = (255 * motorController->getTorqueActual()) / motorController->getTorqueAvailable();
- outData[0] = 1;
- outData[3] = (uint8_t)(temp & 0xFF);
- return true;
- break;
- case 5: //Engine Coolant Temp (A - 40) = Degrees Centigrade
- //our code stores temperatures as a signed integer for tenths of a degree so translate
- temp = motorController->getTemperatureSystem() / 10;
- if (temp < -40) temp = -40;
- if (temp > 215) temp = 215;
- temp += 40;
- outData[0] = 1; //returning only one byte
- outData[3] = (uint8_t)(temp);
- return true;
- break;
- case 0xC: //Engine RPM (A * 256 + B) / 4
- temp = motorController->getSpeedActual() * 4; //we store in RPM while the PID code wants quarter rpms
- outData[0] = 2;
- outData[3] = (uint8_t)(temp / 256);
- outData[4] = (uint8_t)(temp);
- return true;
- break;
- case 0x11: //Throttle position (A * 100 / 255) - Percentage
- temp = motorController->getThrottle() / 10; //getThrottle returns in 10ths of a percent
- if (temp < 0) temp = 0; //negative throttle can't be shown for OBDII
- temp = (255 * temp) / 100;
- outData[0] = 1;
- outData[3] = (uint8_t)(temp);
- return true;
- break;
- case 0x1C: //Standard supported (We return 1 = OBDII)
- outData[0] = 1;
- outData[3] = 1;
- return true;
- break;
- case 0x1F: //runtime since engine start (A*256 + B)
- outData[0] = 2;
- outData[3] = 0; //TODO: Get the actual runtime.
- outData[4] = 0;
- return true;
- break;
- case 0x20: //pids supported (next 32 pids - formatted just like PID 0)
- outData[0] = 4;
- outData[3] = 0b10000000; //pids 0x21 - 0x28 - starting with pid 0x21 in the MSB and going from there
- outData[4] = 0b00000010; //pids 0x29 - 0x30
- outData[5] = 0b00000000; //pids 0x31 - 0x38
- outData[6] = 0b00000001; //pids 0x39 - 0x40
- return true;
- break;
- case 0x21: //Distance traveled with fault light lit (A*256 + B) - In km
- outData[0] = 2;
- outData[3] = 0; //TODO: Can we get this information?
- outData[4] = 0;
- return true;
- break;
- case 0x2F: //Fuel level (A * 100 / 255) - Percentage
- outData[0] = 1;
- outData[3] = 0; //TODO: finish BMS interface and get this value
- return true;
- break;
- case 0x40: //PIDs supported, next 32
- outData[0] = 4;
- outData[3] = 0b00000000; //pids 0x41 - 0x48 - starting with pid 0x41 in the MSB and going from there
- outData[4] = 0b00000000; //pids 0x49 - 0x50
- outData[5] = 0b10000000; //pids 0x51 - 0x58
- outData[6] = 0b00000001; //pids 0x59 - 0x60
- return true;
- break;
- case 0x51: //What type of fuel do we use? (We use 8 = electric, presumably.)
- outData[0] = 1;
- outData[3] = 8;
- return true;
- break;
- case 0x60: //PIDs supported, next 32
- outData[0] = 4;
- outData[3] = 0b11100000; //pids 0x61 - 0x68 - starting with pid 0x61 in the MSB and going from there
- outData[4] = 0b00000000; //pids 0x69 - 0x70
- outData[5] = 0b00000000; //pids 0x71 - 0x78
- outData[6] = 0b00000000; //pids 0x79 - 0x80
- return true;
- break;
- case 0x61: //Driver requested torque (A-125) - Percentage
- temp = (100 * motorController->getTorqueRequested()) / motorController->getTorqueAvailable();
- temp += 125;
- outData[0] = 1;
- outData[3] = (uint8_t)temp;
- return true;
- break;
- case 0x62: //Actual Torque delivered (A-125) - Percentage
- temp = (100 * motorController->getTorqueActual()) / motorController->getTorqueAvailable();
- temp += 125;
- outData[0] = 1;
- outData[3] = (uint8_t)temp;
- return true;
- break;
- case 0x63: //Reference torque for engine - presumably max torque - A*256 + B - Nm
- temp = motorController->getTorqueAvailable();
- outData[0] = 2;
- outData[3] = (uint8_t)(temp / 256);
- outData[4] = (uint8_t)(temp & 0xFF);
- return true;
- break;
- }
- return false;
+bool OBD2Handler::processShowData(uint16_t pid, byte *inData, byte *outData)
+{
+ int temp;
+
+
+ switch (pid) {
+ case 0: //pids 1-0x20 that we support - bitfield
+ //returns 4 bytes so immediately indicate that.
+ outData[0] = 4;
+ outData[3] = 0b11011000; //pids 1 - 8 - starting with pid 1 in the MSB and going from there
+ outData[4] = 0b00010000; //pids 9 - 0x10
+ outData[5] = 0b10000000; //pids 0x11 - 0x18
+ outData[6] = 0b00010011; //pids 0x19 - 0x20
+ return true;
+ break;
+
+ case 1: //Returns 32 bits but we really can only support the first byte which has bit 7 = Malfunction? Bits 0-6 = # of DTCs
+ outData[0] = 4;
+ outData[3] = 0; //TODO: We aren't properly keeping track of faults yet but when we do fix this.
+ outData[4] = 0; //these next three are really related to ICE diagnostics
+ outData[5] = 0; //so ignore them.
+ outData[6] = 0;
+ return true;
+ break;
+
+ case 2: //Freeze DTC
+ return false; //don't support freeze framing yet. Might be useful in the future.
+ break;
+
+ case 4: //Calculated engine load (A * 100 / 255) - Percentage
+ temp = (255 * motorController->getTorqueActual()) / motorController->getTorqueAvailable();
+ outData[0] = 1;
+ outData[3] = (uint8_t)(temp & 0xFF);
+ return true;
+ break;
+
+ case 5: //Engine Coolant Temp (A - 40) = Degrees Centigrade
+ //our code stores temperatures as a signed integer for tenths of a degree so translate
+ temp = motorController->getTemperatureController() / 10;
+
+ if (temp < -40) {
+ temp = -40;
+ }
+
+ if (temp > 215) {
+ temp = 215;
+ }
+
+ temp += 40;
+ outData[0] = 1; //returning only one byte
+ outData[3] = (uint8_t)(temp);
+ return true;
+ break;
+
+ case 0xC: //Engine RPM (A * 256 + B) / 4
+ temp = motorController->getSpeedActual() * 4; //we store in RPM while the PID code wants quarter rpms
+ outData[0] = 2;
+ outData[3] = (uint8_t)(temp / 256);
+ outData[4] = (uint8_t)(temp);
+ return true;
+ break;
+
+ case 0x11: //Throttle position (A * 100 / 255) - Percentage
+ temp = motorController->getThrottleLevel() / 10; //getThrottle returns in 10ths of a percent
+
+ if (temp < 0) {
+ temp = 0; //negative throttle can't be shown for OBDII
+ }
+
+ temp = (255 * temp) / 100;
+ outData[0] = 1;
+ outData[3] = (uint8_t)(temp);
+ return true;
+ break;
+
+ case 0x1C: //Standard supported (We return 1 = OBDII)
+ outData[0] = 1;
+ outData[3] = 1;
+ return true;
+ break;
+
+ case 0x1F: //runtime since engine start (A*256 + B)
+ outData[0] = 2;
+ outData[3] = 0; //TODO: Get the actual runtime.
+ outData[4] = 0;
+ return true;
+ break;
+
+ case 0x20: //pids supported (next 32 pids - formatted just like PID 0)
+ outData[0] = 4;
+ outData[3] = 0b10000000; //pids 0x21 - 0x28 - starting with pid 0x21 in the MSB and going from there
+ outData[4] = 0b00000010; //pids 0x29 - 0x30
+ outData[5] = 0b00000000; //pids 0x31 - 0x38
+ outData[6] = 0b00000001; //pids 0x39 - 0x40
+ return true;
+ break;
+
+ case 0x21: //Distance traveled with fault light lit (A*256 + B) - In km
+ outData[0] = 2;
+ outData[3] = 0; //TODO: Can we get this information?
+ outData[4] = 0;
+ return true;
+ break;
+
+ case 0x2F: //Fuel level (A * 100 / 255) - Percentage
+ outData[0] = 1;
+ outData[3] = 0; //TODO: finish BMS interface and get this value
+ return true;
+ break;
+
+ case 0x40: //PIDs supported, next 32
+ outData[0] = 4;
+ outData[3] = 0b00000000; //pids 0x41 - 0x48 - starting with pid 0x41 in the MSB and going from there
+ outData[4] = 0b00000000; //pids 0x49 - 0x50
+ outData[5] = 0b10000000; //pids 0x51 - 0x58
+ outData[6] = 0b00000001; //pids 0x59 - 0x60
+ return true;
+ break;
+
+ case 0x51: //What type of fuel do we use? (We use 8 = electric, presumably.)
+ outData[0] = 1;
+ outData[3] = 8;
+ return true;
+ break;
+
+ case 0x60: //PIDs supported, next 32
+ outData[0] = 4;
+ outData[3] = 0b11100000; //pids 0x61 - 0x68 - starting with pid 0x61 in the MSB and going from there
+ outData[4] = 0b00000000; //pids 0x69 - 0x70
+ outData[5] = 0b00000000; //pids 0x71 - 0x78
+ outData[6] = 0b00000000; //pids 0x79 - 0x80
+ return true;
+ break;
+
+ case 0x61: //Driver requested torque (A-125) - Percentage
+ temp = (100 * motorController->getTorqueRequested()) / motorController->getTorqueAvailable();
+ temp += 125;
+ outData[0] = 1;
+ outData[3] = (uint8_t) temp;
+ return true;
+ break;
+
+ case 0x62: //Actual Torque delivered (A-125) - Percentage
+ temp = (100 * motorController->getTorqueActual()) / motorController->getTorqueAvailable();
+ temp += 125;
+ outData[0] = 1;
+ outData[3] = (uint8_t) temp;
+ return true;
+ break;
+
+ case 0x63: //Reference torque for engine - presumably max torque - A*256 + B - Nm
+ temp = motorController->getTorqueAvailable();
+ outData[0] = 2;
+ outData[3] = (uint8_t)(temp / 256);
+ outData[4] = (uint8_t)(temp & 0xFF);
+ return true;
+ break;
+ }
+
+ return false;
}
-bool OBD2Handler::processShowCustomData(uint16_t pid, char *inData, char *outData) {
- switch (pid) {
- }
- return false;
+bool OBD2Handler::processShowCustomData(uint16_t pid, byte *inData, byte *outData)
+{
+ switch (pid) {
+ }
+ return false;
}
diff --git a/OBD2Handler.h b/OBD2Handler.h
index 132b64e..2c07bff 100644
--- a/OBD2Handler.h
+++ b/OBD2Handler.h
@@ -35,25 +35,24 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
#include "DeviceManager.h"
#include "TickHandler.h"
#include "CanHandler.h"
-#include "constants.h"
-class OBD2Handler {
+class OBD2Handler
+{
public:
- bool processRequest(uint8_t mode, uint8_t pid, char *inData, char *outData);
- static OBD2Handler *getInstance();
+ bool processRequest(byte *inData, byte *outData);
+ static OBD2Handler *getInstance();
protected:
private:
- OBD2Handler(); //it's not right to try to directly instantiate this class
- bool processShowData(uint8_t pid, char *inData, char *outData);
- bool processShowCustomData(uint16_t pid, char *inData, char *outData);
-
- static OBD2Handler *instance;
- MotorController* motorController;
- Throttle* accelPedal;
- Throttle* brakePedal;
- BatteryManager *BMS;
+ OBD2Handler(); //it's not right to try to directly instantiate this class
+ bool processShowData(uint16_t pid, byte *inData, byte *outData);
+ bool processShowCustomData(uint16_t pid, byte *inData, byte *outData);
+
+ MotorController* motorController;
+ Throttle* accelPedal;
+ Throttle* brakePedal;
+ BatteryManager *BMS;
};
-#endif
\ No newline at end of file
+#endif
diff --git a/OrionBMS.cpp b/OrionBMS.cpp
new file mode 100644
index 0000000..bf7467f
--- /dev/null
+++ b/OrionBMS.cpp
@@ -0,0 +1,294 @@
+/*
+ * OrionBMS.cpp
+ *
+ * Controller for Orion Battery Management System
+ *
+ Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
+
+ 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 "OrionBMS.h"
+
+OrionBMS::OrionBMS() :
+ BatteryManager()
+{
+ prefsHandler = new PrefHandler(ORIONBMS);
+ commonName = "Orion BMS";
+ relayStatus = 0;
+ flags = 0;
+ currentLimit = 0;
+ packSummedVoltage = 0;
+ canTickCounter = 0;
+}
+
+void OrionBMS::setup()
+{
+ BatteryManager::setup();
+
+ tickHandler.attach(this, CFG_TICK_INTERVAL_BMS_ORION);
+ canHandlerEv.attach(this, ORION_CAN_MASKED_ID, ORION_CAN_MASK, false);
+ ready = true;
+}
+
+/**
+ * Tear down the device in a safe way.
+ */
+void OrionBMS::tearDown()
+{
+ BatteryManager::tearDown();
+ canHandlerEv.detach(this, ORION_CAN_MASKED_ID, ORION_CAN_MASK);
+}
+
+/*
+ * Process event from the tick handler.
+ */
+void OrionBMS::handleTick()
+{
+ BatteryManager::handleTick(); // call parent
+
+ // check if we get a message, if not received for 10 sec, the BMS is not ready
+ if (canTickCounter < 20) {
+ canTickCounter++;
+ } else {
+ ready = false;
+ running = false;
+ if (status.getSystemState() == Status::charging) {
+ logger.error(this, "no message from BMS received for 10sec");
+ status.setSystemState(Status::error);
+ }
+ }
+}
+
+void OrionBMS::handleCanFrame(CAN_FRAME *frame)
+{
+ switch (frame->id) {
+ case ORION_CAN_ID_PACK:
+ processPack(frame->data.bytes);
+ break;
+ case ORION_CAN_ID_LIMITS:
+ processLimits(frame->data.bytes);
+ break;
+ case ORION_CAN_ID_CELL_VOLTAGE:
+ processCellVoltage(frame->data.bytes);
+ break;
+ case ORION_CAN_ID_CELL_RESISTANCE:
+ processCellResistance(frame->data.bytes);
+ break;
+ case ORION_CAN_ID_HEALTH:
+ processHealth(frame->data.bytes);
+ break;
+ case ORION_CAN_ID_TEMPERATURE:
+ processTemperature(frame->data.bytes);
+ break;
+ }
+}
+
+void OrionBMS::processPack(uint8_t data[])
+{
+ canTickCounter = 0;
+ packCurrent = ((data[0] << 8) | data[1]); // byte 0+1: pack current (0.1A)
+ packVoltage = ((data[2] << 8) | data[3]); // byte 2+3: pack voltage (0.1V)
+ packSummedVoltage = ((data[4] << 8) | data[5]); // byte 4+5: pack voltage (0.1V)
+ flags = data[6];
+ status.bmsVoltageFailsafe = (flags & voltageFailsafe) ? true : false;
+ status.bmsCurrentFailsafe = (flags & currentFailsafe) ? true : false;
+ status.bmsDepleted = (flags & depleted) ? true : false;
+ status.bmsBalancingActive = (flags & balancingActive) ? true : false;
+ status.bmsDtcWeakCellFault = (flags & dtcWeakCellFault) ? true : false;
+ status.bmsDtcLowCellVolage = (flags & dtcLowCellVolage) ? true : false;
+ status.bmsDtcHVIsolationFault = (flags & dtcHVIsolationFault) ? true : false;
+ status.bmsDtcVoltageRedundancyFault = (flags & dtcVoltageRedundancyFault) ? true : false;
+ soc = data[7]; // byte 7: temperature of BMS (1C)
+ if (logger.isDebug()) {
+ logger.debug(this, "pack current: %fA, voltage: %fV (summed: %fV), flags: %#08x, soc: %.1f", (float) packCurrent / 10.0F,
+ (float) packVoltage / 10.0F, (float) packSummedVoltage / 10.0F, flags, (float) soc / 2.0F);
+ }
+}
+
+void OrionBMS::processLimits(uint8_t data[])
+{
+ canTickCounter = 0;
+ dischargeLimit = ((data[0] << 8) | data[1]); // byte 0+1: pack discharge current limit (DCL) (1A)
+ allowDischarge = (dischargeLimit > 0);
+ chargeLimit = ((data[2] << 8) | data[3]); // byte 2+3: pack charge current limit (CCL) (1A)
+ allowCharge = (chargeLimit > 0);
+ currentLimit = ((data[4] << 8) | data[5]); // byte 4+5: bitfield with reason for current limmitation
+ status.bmsDclLowSoc = (currentLimit & dclLowSoc) ? true : false;
+ status.bmsDclHighCellResistance = (currentLimit & dclHighCellResistance) ? true : false;
+ status.bmsDclTemperature = (currentLimit & dclTemperature) ? true : false;
+ status.bmsDclLowCellVoltage = (currentLimit & dclLowCellVoltage) ? true : false;
+ status.bmsDclLowPackVoltage = (currentLimit & dclLowPackVoltage) ? true : false;
+ status.bmsDclCclVoltageFailsafe = (currentLimit & dclCclVoltageFailsafe) ? true : false;
+ status.bmsDclCclCommunication = (currentLimit & dclCclCommunication) ? true : false;
+ status.bmsCclHighSoc = (currentLimit & cclHighSoc) ? true : false;
+ status.bmsCclHighCellResistance = (currentLimit & cclHighCellResistance) ? true : false;
+ status.bmsCclTemperature = (currentLimit & cclTemperature) ? true : false;
+ status.bmsCclHighCellVoltage = (currentLimit & cclHighCellVoltage) ? true : false;
+ status.bmsCclHighPackVoltage = (currentLimit & cclHighPackVoltage) ? true : false;
+ status.bmsCclChargerLatch = (currentLimit & cclChargerLatch) ? true : false;
+ status.bmsCclAlternate = (currentLimit & cclAlternate) ? true : false;
+ relayStatus = data[6];
+ status.bmsRelayDischarge = (relayStatus & relayDischarge) ? true : false; // Bit #1 (0x01): Discharge relay enabled
+ status.bmsRelayCharge = (relayStatus & relayCharge) ? true : false; // Bit #2 (0x02): Charge relay enabled
+ chargerEnabled = (relayStatus & chagerSafety) ? true : false; // Bit #3 (0x04): Charger safety enabled
+ status.bmsChagerSafety = chargerEnabled;
+ status.bmsDtcPresent = (relayStatus & dtcPresent) ? true : false; // Bit #4 (0x08): Malfunction indicator active (DTC status)
+ if (logger.isDebug()) {
+ logger.debug(this, "discharge limit: %dA, charge limit: %dA, limit flags: %#08x, relay: %#08x", dischargeLimit, chargeLimit, currentLimit,
+ relayStatus);
+ }
+}
+
+void OrionBMS::processCellVoltage(uint8_t data[])
+{
+ canTickCounter = 0;
+ lowestCellVolts = ((data[0] << 8) | data[1]); // byte 0+1: low cell voltage (0.0001V)
+ lowestCellVoltsId = data[2]; // byte 2: low cell voltage ID (0-180)
+ highestCellVolts = ((data[3] << 8) | data[4]); // byte 3+4: high cell voltage (0.0001V)
+ highestCellVoltsId = data[5]; // byte 5: high cell voltage ID (0-180)
+ averageCellVolts = ((data[6] << 8) | data[7]); // byte 6+7: average cell voltage (0.0001V)
+ if (logger.isDebug()) {
+ logger.debug(this, "low cell: %fV (%d), high cell: %fV (%d), avg: %fV", (float) lowestCellVolts / 10000.0F, lowestCellVoltsId,
+ (float) highestCellVolts / 10000.0F, highestCellVoltsId, (float) averageCellVolts / 10000.0F);
+ }
+}
+
+void OrionBMS::processCellResistance(uint8_t data[])
+{
+ canTickCounter = 0;
+ lowestCellResistance = ((data[0] << 8) | data[1]); // byte 0+1: low cell resistance (0.01 mOhm)
+ lowestCellResistanceId = data[2]; // byte 2: low cell resistance ID (0-180)
+ highestCellResistance = ((data[3] << 8) | data[4]); // byte 3+4: high cell resistance (0.01 mOhm)
+ highestCellResistanceId = data[5]; // byte 5: high cell resistance ID (0-180)
+ averageCellResistance = ((data[6] << 8) | data[7]); // byte 6+7: average cell resistance (0.01 mOhm)
+ if (logger.isDebug()) {
+ logger.debug(this, "low cell: %fmOhm (%d), high cell: %fmOhm (%d), avg: %fmOhm", (float) lowestCellResistance / 100.0F,
+ lowestCellResistanceId, (float) highestCellResistance / 100.0F, highestCellResistanceId, (float) averageCellResistance / 100.0F);
+ }
+}
+
+void OrionBMS::processHealth(uint8_t data[])
+{
+ canTickCounter = 0;
+ packHealth = data[0]; // byte 0: pack health (1%)
+ packCycles = ((data[1] << 8) | data[2]); // byte 1+2: number of total pack cycles
+ packResistance = ((data[3] << 8) | data[4]); // byte 3+4: pack resistance (1 mOhm)
+ packAmphours = ((data[5] << 8) | data[6]); // byte 3+4: pack resistance (1 mOhm)
+ if (logger.isDebug()) {
+ logger.debug(this, "pack health: %d, pack cycles: %d, pack Resistance: %dmOhm, pack charge: %.1fAh", packHealth,
+ packCycles, packResistance, (float) packAmphours / 10.0F);
+ }
+}
+
+void OrionBMS::processTemperature(uint8_t data[])
+{
+ canTickCounter = 0;
+ lowestCellTemp = data[0] * 10;
+ lowestCellTempId = data[1];
+ highestCellTemp = data[2] * 10;
+ highestCellTempId = data[3];
+ systemTemperature = data[4] * 10;
+ if (logger.isDebug()) {
+ logger.debug(this, "low temp: %dC (%d), high temp: %dC (%d), sys temp: %dC", lowestCellTemp, lowestCellTempId,
+ highestCellTemp, highestCellTempId, systemTemperature);
+ }
+}
+
+DeviceId OrionBMS::getId()
+{
+ return (ORIONBMS);
+}
+
+bool OrionBMS::hasPackVoltage()
+{
+ return true;
+}
+
+bool OrionBMS::hasPackCurrent()
+{
+ return true;
+}
+
+bool OrionBMS::hasCellTemperatures()
+{
+ return true;
+}
+
+bool OrionBMS::hasSoc()
+{
+ return true;
+}
+
+bool OrionBMS::hasAmpHours()
+{
+ return true;
+}
+
+bool OrionBMS::hasChargeLimit()
+{
+ return true;
+}
+
+bool OrionBMS::hasDischargeLimit()
+{
+ return true;
+}
+
+bool OrionBMS::hasAllowCharging()
+{
+ return true;
+}
+
+bool OrionBMS::hasAllowDischarging()
+{
+ return true;
+}
+
+bool OrionBMS::hasCellVoltages()
+{
+ return true;
+}
+
+bool OrionBMS::hasCellResistance()
+{
+ return true;
+}
+
+bool OrionBMS::hasPackHealth()
+{
+ return true;
+}
+
+bool OrionBMS::hasPackCycles()
+{
+ return true;
+}
+
+bool OrionBMS::hasPackResistance()
+{
+ return true;
+}
+
+bool OrionBMS::hasChargerEnabled()
+{
+ return true;
+}
diff --git a/OrionBMS.h b/OrionBMS.h
new file mode 100644
index 0000000..5ca1d61
--- /dev/null
+++ b/OrionBMS.h
@@ -0,0 +1,130 @@
+/*
+ * OrionBMS.h
+ *
+ * Controller for Orion Battery Management System
+ *
+Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
+
+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 ORIONBMS_H_
+#define ORIONBMS_H_
+
+#include
+#include "config.h"
+#include "Device.h"
+#include "DeviceManager.h"
+#include "BatteryManager.h"
+#include "CanHandler.h"
+#include "FaultHandler.h"
+#include "CRC8.h"
+
+// CAN bus id's for frames received from Orion BMS
+#define ORION_CAN_ID_PACK 0x6b0 // receive actual values information 110 1011 0000
+#define ORION_CAN_ID_LIMITS 0x6b1 // receive actual values information 110 1011 0001
+#define ORION_CAN_ID_CELL_VOLTAGE 0x6b2 // receive actual values information 110 1011 0010
+#define ORION_CAN_ID_CELL_RESISTANCE 0x6b3 // receive actual values information 110 1011 0011
+#define ORION_CAN_ID_HEALTH 0x6b4 // receive actual values information 110 1011 0100
+#define ORION_CAN_ID_TEMPERATURE 0x6b5 // receive actual values information 110 1011 0101
+#define ORION_CAN_MASK 0x7f8 // mask for above id's 111 1111 1000
+#define ORION_CAN_MASKED_ID 0x6b0 // masked id for above id's 110 1011 0000
+
+class OrionBMS : public BatteryManager, CanObserver
+{
+public:
+
+ enum Orion_Flags {
+ voltageFailsafe = 1 << 0,
+ currentFailsafe = 1 << 1,
+ depleted = 1 << 2,
+ balancingActive = 1 << 3,
+ dtcWeakCellFault = 1 << 4,
+ dtcLowCellVolage = 1 << 5,
+ dtcHVIsolationFault = 1 << 6,
+ dtcVoltageRedundancyFault = 1 << 7
+ };
+
+ enum Orion_CurrentLimit {
+ dclLowSoc = 1 << 0, //DCL Reduced Due To Low SOC (Bit #0)
+ dclHighCellResistance = 1 << 1, //DCL Reduced Due To High Cell Resistance (Bit #1)
+ dclTemperature = 1 << 2, //DCL Reduced Due To Temperature (Bit #2)
+ dclLowCellVoltage = 1 << 3, //DCL Reduced Due To Low Cell Voltage (Bit #3)
+ dclLowPackVoltage = 1 << 4, //DCL Reduced Due To Low Pack Voltage (Bit #4)
+ dclCclVoltageFailsafe = 1 << 6, //DCL and CCL Reduced Due To Voltage Failsafe (Bit #6)
+ dclCclCommunication = 1 << 7, //DCL and CCL Reduced Due To Communication Failsafe (Bit #7): This only applies if there are multiple BMS units connected together in series over CANBUS.
+ cclHighSoc = 1 << 9, //CCL Reduced Due To High SOC (Bit #9)
+ cclHighCellResistance = 1 << 10, //CCL Reduced Due To High Cell Resistance (Bit #10)
+ cclTemperature = 1 << 11, //CCL Reduced Due To Temperature (Bit #11)
+ cclHighCellVoltage = 1 << 12, //CCL Reduced Due To High Cell Voltage (Bit #12)
+ cclHighPackVoltage = 1 << 13, //CCL Reduced Due To High Pack Voltage (Bit #13)
+ cclChargerLatch = 1 << 14, //CCL Reduced Due To Charger Latch (Bit #14): This means the CCL is likely 0A because the charger has been turned off. This latch is removed when the Charge Power signal is removed and re-applied (ie: unplugging the car and plugging it back in).
+ cclAlternate = 1 << 15 //CCL Reduced Due To Alternate Current Limit [MPI] (Bit #15)
+ };
+
+ enum Orion_RelayStatus {
+ relayDischarge = 1 << 0, // Bit #0 (0x01): Discharge relay enabled
+ relayCharge = 1 << 1, // Bit #1 (0x02): Charge relay enabled
+ chagerSafety = 1 << 2, // Bit #2 (0x04): Charger safety enabled
+ dtcPresent = 1 << 3, // Bit #3 (0x08): Malfunction indicator active (DTC status)
+ multiPurposeInput = 1 << 4, // Bit #4 (0x10): Multi-Purpose Input signal status
+ alwaysOn = 1 << 5, // Bit #5 (0x20): Always-on signal status
+ isReady = 1 << 6, // Bit #6 (0x40): Is-Ready signal status
+ isCharging = 1 << 7 // Bit #7 (0x80): Is-Charging signal status
+ };
+
+ OrionBMS();
+ void setup();
+ void tearDown();
+ void handleTick();
+ void handleCanFrame(CAN_FRAME *frame);
+ DeviceId getId();
+ bool hasPackVoltage();
+ bool hasPackCurrent();
+ bool hasCellTemperatures();
+ bool hasSoc();
+ bool hasAmpHours();
+ bool hasChargeLimit();
+ bool hasDischargeLimit();
+ bool hasAllowCharging();
+ bool hasAllowDischarging();
+ bool hasCellVoltages();
+ bool hasCellResistance();
+ bool hasPackHealth();
+ bool hasPackCycles();
+ bool hasPackResistance();
+ bool hasChargerEnabled();
+
+protected:
+private:
+ uint8_t relayStatus, flags;
+ uint16_t currentLimit;
+ uint16_t packSummedVoltage;
+ uint8_t canTickCounter;
+ void processPack(uint8_t data[]);
+ void processLimits(uint8_t data[]);
+ void processCellVoltage(uint8_t data[]);
+ void processCellResistance(uint8_t data[]);
+ void processHealth(uint8_t data[]);
+ void processTemperature(uint8_t data[]);
+};
+
+#endif
diff --git a/PerfTimer.cpp b/PerfTimer.cpp
new file mode 100644
index 0000000..373eb05
--- /dev/null
+++ b/PerfTimer.cpp
@@ -0,0 +1,99 @@
+/*
+ * PerfTimer.cpp
+ *
+ * Provides the ability to track performance of a code section in terms of runtime.
+ *
+ Copyright (c) 2014 Collin Kidder, Michael Neuweiler, Charles Galpin
+
+ 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 "PerfTimer.h"
+#include "Logger.h"
+
+PerfTimer::PerfTimer()
+{
+ reset();
+}
+
+void PerfTimer::start()
+{
+ startTime = micros();
+}
+
+void PerfTimer::stop()
+{
+ int numTicks;
+
+ endTime = micros();
+
+ numTicks = endTime - startTime;
+
+ if (numTicks < timeMin) timeMin = numTicks;
+ if (numTicks > timeMax) timeMax = numTicks;
+
+ accumVals++;
+ timeAccum += numTicks;
+
+ //Auto condense the average if it starts to get too close to the upper limit
+ if (timeAccum > 3500000000ul) condenseAvg();
+
+}
+
+uint32_t PerfTimer::getMin()
+{
+ return timeMin;
+}
+
+uint32_t PerfTimer::getMax()
+{
+ return timeMax;
+}
+
+uint32_t PerfTimer::getAvg()
+{
+ if (accumVals == 0) return 0;
+ return timeAccum / accumVals;
+}
+
+void PerfTimer::condenseAvg()
+{
+ if (accumVals == 0) return;
+ timeAccum /= accumVals;
+ accumVals = 1;
+}
+
+void PerfTimer::reset()
+{
+ timeMin = 1000000;
+ timeMax = 0;
+ timeAccum = 0;
+ accumVals = 0;
+ startTime = 0;
+ endTime = 0;
+}
+
+void PerfTimer::printValues()
+{
+ logger.console("Min/Max/Avg (uS) -> %i/%i/%i", getMin(), getMax(), getAvg());
+ logger.console("Min/Max/Avg (approx cycles) -> %i/%i/%i", getMin() * 84, getMax() * 84, getAvg() * 84);
+}
diff --git a/sys_io.h b/PerfTimer.h
similarity index 59%
rename from sys_io.h
rename to PerfTimer.h
index ad6f296..79213f2 100644
--- a/sys_io.h
+++ b/PerfTimer.h
@@ -1,9 +1,9 @@
/*
- * sys_io.h
+ * PerfTimer.h
*
- * Handles raw interaction with system I/O
+ * Provides the ability to track performance of a code section in terms of runtime.
*
-Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
+Copyright (c) 2014 Collin Kidder, Michael Neuweiler, Charles Galpin
Permission is hereby granted, free of charge, to any person obtaining
a copy of this software and associated documentation files (the
@@ -24,33 +24,34 @@ 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 SYS_IO_H_
-#define SYS_IO_H_
+#ifndef PERF_TIME_H_
+#define PERF_TIME_H_
#include
#include "config.h"
-#include "eeprom_layout.h"
-#include "PrefHandler.h"
-typedef struct {
- uint16_t offset;
- uint16_t gain;
-} ADC_COMP;
-
-void setup_sys_io();
-uint16_t getAnalog(uint8_t which); //get value of one of the 4 analog inputs
-uint16_t getDiffADC(uint8_t which);
-uint16_t getRawADC(uint8_t which);
-boolean getDigital(uint8_t which); //get value of one of the 4 digital inputs
-void setOutput(uint8_t which, boolean active); //set output high or not
-boolean getOutput(uint8_t which); //get current value of output state (high?)
-void setupFastADC();
-void sys_io_adc_poll();
-void sys_early_setup();
-
-
-
-#endif
+class PerfTimer {
+public:
+ PerfTimer();
+ void start();
+ void stop();
+ uint32_t getMin();
+ uint32_t getMax();
+ uint32_t getAvg();
+ void condenseAvg();
+ void reset();
+ void printValues();
+protected:
+private:
+ uint32_t timeMin; //the lowest time we've seen
+ uint32_t timeMax; //the highest time we've seen
+ uint32_t timeAccum; //accumulation of all the values we've stored
+ uint32_t accumVals; //total # of values accumulated so far
+ uint32_t startTime;
+ uint32_t endTime;
+};
+
+#endif
\ No newline at end of file
diff --git a/PotBrake.cpp b/PotBrake.cpp
index ef77ac5..a0356c0 100644
--- a/PotBrake.cpp
+++ b/PotBrake.cpp
@@ -30,123 +30,138 @@
* Constructor
* Set which ADC channel to use
*/
-PotBrake::PotBrake() : Throttle() {
- prefsHandler = new PrefHandler(POTBRAKEPEDAL);
- commonName = "Potentiometer (analog) brake";
+PotBrake::PotBrake() : Throttle()
+{
+ prefsHandler = new PrefHandler(POTBRAKEPEDAL);
+ commonName = "Potentiometer (analog) brake";
}
/*
* Setup the device.
*/
-void PotBrake::setup() {
- TickHandler::getInstance()->detach(this); // unregister from TickHandler first
+void PotBrake::setup()
+{
+ Throttle::setup(); //call base class
- Logger::info("add device: PotBrake (id: %X, %X)", POTBRAKEPEDAL, this);
+ //set digital ports to inputs and pull them up all inputs currently active low
+ //pinMode(THROTTLE_INPUT_BRAKELIGHT, INPUT_PULLUP); //Brake light switch
- Throttle::setup(); //call base class
+ ready = true;
- //set digital ports to inputs and pull them up all inputs currently active low
- //pinMode(THROTTLE_INPUT_BRAKELIGHT, INPUT_PULLUP); //Brake light switch
-
- loadConfiguration();
- TickHandler::getInstance()->attach(this, CFG_TICK_INTERVAL_POT_THROTTLE);
+ tickHandler.attach(this, CFG_TICK_INTERVAL_POT_THROTTLE);
}
/*
* Process a timer event.
*/
-void PotBrake::handleTick() {
- Throttle::handleTick(); // Call parent which controls the workflow
+void PotBrake::handleTick()
+{
+ Throttle::handleTick(); // Call parent which controls the workflow
}
/*
* Retrieve raw input signals from the brake hardware.
*/
-RawSignalData *PotBrake::acquireRawSignal() {
- PotBrakeConfiguration *config = (PotBrakeConfiguration *) getConfiguration();
- sys_io_adc_poll();
- rawSignal.input1 = getAnalog(config->AdcPin1);
- return &rawSignal;
+RawSignalData *PotBrake::acquireRawSignal()
+{
+ PotBrakeConfiguration *config = (PotBrakeConfiguration *) getConfiguration();
+ systemIO.ADCPoll();
+ rawSignal.input1 = systemIO.getAnalogIn(config->AdcPin1);
+ return &rawSignal;
}
/*
* Perform sanity check on the ADC input values.
*/
-bool PotBrake::validateSignal(RawSignalData *rawSignal) {
- PotBrakeConfiguration *config = (PotBrakeConfiguration *) getConfiguration();
-
- if (rawSignal->input1 > (config->maximumLevel1 + CFG_THROTTLE_TOLERANCE)) {
- if (status == OK)
- Logger::error(POTBRAKEPEDAL, (char *)Constants::valueOutOfRange, rawSignal->input1);
- status = ERR_HIGH_T1;
- return true; // even if it's too high, let it process and apply full regen !
- }
- if (rawSignal->input1 < (config->minimumLevel1 - CFG_THROTTLE_TOLERANCE)) {
- if (status == OK)
- Logger::error(POTBRAKEPEDAL, (char *)Constants::valueOutOfRange, rawSignal->input1);
- status = ERR_LOW_T1;
- return false;
- }
-
- // all checks passed -> brake is OK
- if (status != OK)
- Logger::info(POTBRAKEPEDAL, (char *)Constants::normalOperation);
- status = OK;
- return true;
+bool PotBrake::validateSignal(RawSignalData *rawSignal)
+{
+ PotBrakeConfiguration *config = (PotBrakeConfiguration *) getConfiguration();
+
+ if (rawSignal->input1 > (config->maximumLevel + CFG_THROTTLE_TOLERANCE)) {
+ if (throttleStatus == OK) {
+ logger.error(this, VALUE_OUT_OF_RANGE, rawSignal->input1);
+ }
+
+ throttleStatus = ERR_HIGH_T1;
+ return true; // even if it's too high, let it process and apply full regen !
+ }
+
+ if (rawSignal->input1 < (config->minimumLevel - CFG_THROTTLE_TOLERANCE)) {
+ if (throttleStatus == OK) {
+ logger.error(this, VALUE_OUT_OF_RANGE, rawSignal->input1);
+ }
+
+ throttleStatus = ERR_LOW_T1;
+ return false;
+ }
+
+ // all checks passed -> brake is OK
+ if (throttleStatus != OK) {
+ logger.info(this, NORMAL_OPERATION);
+ }
+
+ throttleStatus = OK;
+ return true;
}
/*
* Convert the raw ADC values to a range from 0 to 1000 (per mille) according
* to the specified range and the type of potentiometer.
*/
-uint16_t PotBrake::calculatePedalPosition(RawSignalData *rawSignal) {
- PotBrakeConfiguration *config = (PotBrakeConfiguration *) getConfiguration();
- uint16_t calcBrake1, clampedLevel;
-
- if (config->maximumLevel1 == 0) //brake processing disabled if max is 0
- return 0;
-
- clampedLevel = constrain(rawSignal->input1, config->minimumLevel1, config->maximumLevel1);
- calcBrake1 = map(clampedLevel, config->minimumLevel1, config->maximumLevel1, (uint16_t) 0, (uint16_t) 1000);
-
- //This prevents flutter in the ADC readings of the brake from slamming regen on intermittently
- // just because the value fluttered a couple of numbers. This makes sure that we're actually
- // pushing the pedal. Without this even a small flutter at the brake will send minregen
- // out and ignore the accelerator. That'd be unpleasant.
- if (calcBrake1 < 15)
- calcBrake1 = 0;
-
- return calcBrake1;
+uint16_t PotBrake::calculatePedalPosition(RawSignalData *rawSignal)
+{
+ PotBrakeConfiguration *config = (PotBrakeConfiguration *) getConfiguration();
+ uint16_t calcBrake1, clampedLevel;
+
+ if (config->maximumLevel == 0) { //brake processing disabled if max is 0
+ return 0;
+ }
+
+ clampedLevel = constrain(rawSignal->input1, config->minimumLevel, config->maximumLevel);
+ calcBrake1 = map(clampedLevel, config->minimumLevel, config->maximumLevel, (uint16_t) 0, (uint16_t) 1000);
+
+ //This prevents flutter in the ADC readings of the brake from slamming regen on intermittently
+ // just because the value fluttered a couple of numbers. This makes sure that we're actually
+ // pushing the pedal. Without this even a small flutter at the brake will send minregen
+ // out and ignore the accelerator. That'd be unpleasant.
+ if (calcBrake1 < 15) {
+ calcBrake1 = 0;
+ }
+
+ return calcBrake1;
}
/*
* Overrides the standard implementation of throttle mapping as different rules apply to
* brake based regen.
*/
-int16_t PotBrake::mapPedalPosition(int16_t pedalPosition) {
- ThrottleConfiguration *config = (ThrottleConfiguration *) getConfiguration();
- int16_t brakeLevel, range;
+int16_t PotBrake::mapPedalPosition(int16_t pedalPosition)
+{
+ ThrottleConfiguration *config = (ThrottleConfiguration *) getConfiguration();
+ int16_t brakeLevel, range;
- range = config->maximumRegen - config->minimumRegen;
- brakeLevel = -10 * range * pedalPosition / 1000;
- brakeLevel -= 10 * config->minimumRegen;
- //Logger::debug(POTBRAKEPEDAL, "level: %d", level);
+ range = config->maximumRegen - config->minimumRegen;
+ brakeLevel = -10 * range * pedalPosition / 1000;
+ brakeLevel -= 10 * config->minimumRegen;
+ //logger.debug(this, "level: %d", level);
- return brakeLevel;
+ return brakeLevel;
}
/*
* Return the device ID
*/
-DeviceId PotBrake::getId() {
- return (POTBRAKEPEDAL);
+DeviceId PotBrake::getId()
+{
+ return (POTBRAKEPEDAL);
}
/*
* Return the device type
*/
-DeviceType PotBrake::getType() {
- return (DEVICE_BRAKE);
+DeviceType PotBrake::getType()
+{
+ return (DEVICE_BRAKE);
}
/*
@@ -154,50 +169,53 @@ DeviceType PotBrake::getType() {
* If possible values are read from EEPROM. If not, reasonable default values
* are chosen and the configuration is overwritten in the EEPROM.
*/
-void PotBrake::loadConfiguration() {
- PotBrakeConfiguration *config = new PotBrakeConfiguration();
- setConfiguration(config);
+void PotBrake::loadConfiguration()
+{
+ PotBrakeConfiguration *config = new PotBrakeConfiguration();
+ setConfiguration(config);
- // we deliberately do not load config via parent class here !
+ // we deliberately do not load config via parent class here !
+ logger.info("Pot brake configuration:");
#ifdef USE_HARD_CODED
- if (false) {
+
+ if (false) {
#else
- if (prefsHandler->checksumValid()) { //checksum is good, read in the values stored in EEPROM
+
+ if (prefsHandler->checksumValid()) { //checksum is good, read in the values stored in EEPROM
#endif
- prefsHandler->read(EETH_BRAKE_MIN, &config->minimumLevel1);
- prefsHandler->read(EETH_BRAKE_MAX, &config->maximumLevel1);
- prefsHandler->read(EETH_MAX_BRAKE_REGEN, &config->maximumRegen);
- prefsHandler->read(EETH_MIN_BRAKE_REGEN, &config->minimumRegen);
- prefsHandler->read(EETH_ADC_1, &config->AdcPin1);
- Logger::debug(POTBRAKEPEDAL, "BRAKE MIN: %l MAX: %l", config->minimumLevel1, config->maximumLevel1);
- Logger::debug(POTBRAKEPEDAL, "Min: %l MaxRegen: %l", config->minimumRegen, config->maximumRegen);
- } else { //checksum invalid. Reinitialize values and store to EEPROM
-
- //these four values are ADC values
- //The next three are tenths of a percent
- config->maximumRegen = BrakeMaxRegenValue; //percentage of full power to use for regen at brake pedal transducer
- config->minimumRegen = BrakeMinRegenValue;
- config->minimumLevel1 = BrakeMinValue;
- config->maximumLevel1 = BrakeMaxValue;
- config->AdcPin1 = BrakeADC;
- saveConfiguration();
- }
+ prefsHandler->read(EETH_BRAKE_MIN, &config->minimumLevel);
+ prefsHandler->read(EETH_BRAKE_MAX, &config->maximumLevel);
+ prefsHandler->read(EETH_MAX_BRAKE_REGEN, &config->maximumRegen);
+ prefsHandler->read(EETH_MIN_BRAKE_REGEN, &config->minimumRegen);
+ prefsHandler->read(EETH_ADC_1, &config->AdcPin1);
+ } else {
+ config->minimumLevel = 100;
+ config->maximumLevel = 3200;
+ config->maximumRegen = 50;
+ config->minimumRegen = 0;
+ config->AdcPin1 = 2;
+ saveConfiguration();
+ }
+
+ logger.info(this, "MIN: %ld, MAX: %ld", config->minimumLevel, config->maximumLevel);
+ logger.info(this, "Min regen: %ld Max Regen: %ld", config->minimumRegen, config->maximumRegen);
}
/*
* Store the current configuration to EEPROM
*/
-void PotBrake::saveConfiguration() {
- PotBrakeConfiguration *config = (PotBrakeConfiguration *) getConfiguration();
-
- // we deliberately do not save config via parent class here !
-
- prefsHandler->write(EETH_BRAKE_MIN, config->minimumLevel1);
- prefsHandler->write(EETH_BRAKE_MAX, config->maximumLevel1);
- prefsHandler->write(EETH_MAX_BRAKE_REGEN, config->maximumRegen);
- prefsHandler->write(EETH_MIN_BRAKE_REGEN, config->minimumRegen);
- prefsHandler->write(EETH_ADC_1, config->AdcPin1);
- prefsHandler->saveChecksum();
+void PotBrake::saveConfiguration()
+{
+ PotBrakeConfiguration *config = (PotBrakeConfiguration *) getConfiguration();
+
+ // we deliberately do not save config via parent class here !
+
+ prefsHandler->write(EETH_BRAKE_MIN, config->minimumLevel);
+ prefsHandler->write(EETH_BRAKE_MAX, config->maximumLevel);
+ prefsHandler->write(EETH_MAX_BRAKE_REGEN, config->maximumRegen);
+ prefsHandler->write(EETH_MIN_BRAKE_REGEN, config->minimumRegen);
+ prefsHandler->write(EETH_ADC_1, config->AdcPin1);
+ prefsHandler->saveChecksum();
}
diff --git a/PotBrake.h b/PotBrake.h
index 000353c..32648e0 100644
--- a/PotBrake.h
+++ b/PotBrake.h
@@ -30,7 +30,7 @@
#include
#include "config.h"
#include "PotThrottle.h"
-#include "sys_io.h"
+#include "SystemIO.h"
#include "TickHandler.h"
#include "Logger.h"
#include "DeviceManager.h"
@@ -42,30 +42,32 @@
*
* NOTE: Because of ThrottleDetector, this currently MUST be the same as PotThrottleConfiguratin !!!
*/
-class PotBrakeConfiguration: public PotThrottleConfiguration {
+class PotBrakeConfiguration: public PotThrottleConfiguration
+{
public:
};
-class PotBrake: public Throttle {
+class PotBrake: public Throttle
+{
public:
- PotBrake();
- void setup();
- void handleTick();
- DeviceId getId();
- DeviceType getType();
+ PotBrake();
+ void setup();
+ void handleTick();
+ DeviceId getId();
+ DeviceType getType();
- RawSignalData *acquireRawSignal();
+ RawSignalData *acquireRawSignal();
- void loadConfiguration();
- void saveConfiguration();
+ void loadConfiguration();
+ void saveConfiguration();
protected:
- bool validateSignal(RawSignalData *);
- uint16_t calculatePedalPosition(RawSignalData *);
- int16_t mapPedalPosition(int16_t);
+ bool validateSignal(RawSignalData *);
+ uint16_t calculatePedalPosition(RawSignalData *);
+ int16_t mapPedalPosition(int16_t);
private:
- RawSignalData rawSignal;
+ RawSignalData rawSignal;
};
#endif /* POT_BRAKE_H_ */
diff --git a/PotThrottle.cpp b/PotThrottle.cpp
index 01593c2..51cdbd1 100644
--- a/PotThrottle.cpp
+++ b/PotThrottle.cpp
@@ -29,181 +29,200 @@
/*
* Constructor
*/
-PotThrottle::PotThrottle() : Throttle() {
- prefsHandler = new PrefHandler(POTACCELPEDAL);
- commonName = "Potentiometer (analog) accelerator";
+PotThrottle::PotThrottle() : Throttle()
+{
+ prefsHandler = new PrefHandler(POTACCELPEDAL);
+ commonName = "Potentiometer (analog) accelerator";
}
/*
* Setup the device.
*/
-void PotThrottle::setup() {
- TickHandler::getInstance()->detach(this); // unregister from TickHandler first
-
- Logger::info("add device: PotThrottle (id: %X, %X)", POTACCELPEDAL, this);
+void PotThrottle::setup()
+{
+ Throttle::setup(); //call base class
+ ready = true;
- loadConfiguration();
+ //set digital ports to inputs and pull them up all inputs currently active low
+ //pinMode(THROTTLE_INPUT_BRAKELIGHT, INPUT_PULLUP); //Brake light switch
- Throttle::setup(); //call base class
-
- //set digital ports to inputs and pull them up all inputs currently active low
- //pinMode(THROTTLE_INPUT_BRAKELIGHT, INPUT_PULLUP); //Brake light switch
-
- TickHandler::getInstance()->attach(this, CFG_TICK_INTERVAL_POT_THROTTLE);
+ tickHandler.attach(this, CFG_TICK_INTERVAL_POT_THROTTLE);
}
/*
* Process a timer event.
*/
-void PotThrottle::handleTick() {
- Throttle::handleTick(); // Call parent which controls the workflow
+void PotThrottle::handleTick()
+{
+ Throttle::handleTick(); // Call parent which controls the workflow
}
/*
* Retrieve raw input signals from the throttle hardware.
*/
-RawSignalData *PotThrottle::acquireRawSignal() {
- PotThrottleConfiguration *config = (PotThrottleConfiguration *) getConfiguration();
- sys_io_adc_poll();
-
- rawSignal.input1 = getAnalog(config->AdcPin1);
- rawSignal.input2 = getAnalog(config->AdcPin2);
- return &rawSignal;
+RawSignalData *PotThrottle::acquireRawSignal()
+{
+ PotThrottleConfiguration *config = (PotThrottleConfiguration *) getConfiguration();
+ systemIO.ADCPoll();
+
+ rawSignal.input1 = systemIO.getAnalogIn(config->AdcPin1);
+ rawSignal.input2 = systemIO.getAnalogIn(config->AdcPin2);
+ return &rawSignal;
}
/*
* Perform sanity check on the ADC input values. The values are normalized (without constraining them)
* and the checks are performed on a 0-1000 scale with a percentage tolerance
*/
-bool PotThrottle::validateSignal(RawSignalData *rawSignal) {
- PotThrottleConfiguration *config = (PotThrottleConfiguration *) getConfiguration();
- int32_t calcThrottle1, calcThrottle2;
+bool PotThrottle::validateSignal(RawSignalData *rawSignal)
+{
+ PotThrottleConfiguration *config = (PotThrottleConfiguration *) getConfiguration();
+ int32_t calcThrottle1, calcThrottle2;
- calcThrottle1 = normalizeInput(rawSignal->input1, config->minimumLevel1, config->maximumLevel1);
- if (config->numberPotMeters == 1 && config->throttleSubType == 2) { // inverted
- calcThrottle1 = 1000 - calcThrottle1;
- }
+ calcThrottle1 = normalizeInput(rawSignal->input1, config->minimumLevel, config->maximumLevel);
-
- if (calcThrottle1 > (1000 + CFG_THROTTLE_TOLERANCE))
- {
- if (status == OK)
- Logger::error(POTACCELPEDAL, "ERR_HIGH_T1: throttle 1 value out of range: %l", calcThrottle1);
- status = ERR_HIGH_T1;
+ if (config->numberPotMeters == 1 && config->throttleSubType == 2) { // inverted
+ calcThrottle1 = 1000 - calcThrottle1;
+ }
+
+ if (calcThrottle1 > (1000 + CFG_THROTTLE_TOLERANCE)) {
+ if (throttleStatus == OK) {
+ logger.error(this, "ERR_HIGH_T1: throttle 1 value out of range: %ld", calcThrottle1);
+ }
faultHandler.raiseFault(POTACCELPEDAL, FAULT_THROTTLE_HIGH_A, true);
- return false;
- }
+
+ throttleStatus = ERR_HIGH_T1;
+ return false;
+ }
else
{
faultHandler.cancelOngoingFault(POTACCELPEDAL, FAULT_THROTTLE_HIGH_A);
}
- if (calcThrottle1 < (0 - CFG_THROTTLE_TOLERANCE)) {
- if (status == OK)
- Logger::error(POTACCELPEDAL, "ERR_LOW_T1: throttle 1 value out of range: %l ", calcThrottle1);
- status = ERR_LOW_T1;
+ if (calcThrottle1 < (0 - CFG_THROTTLE_TOLERANCE)) {
+ if (throttleStatus == OK) {
+ logger.error(this, "ERR_LOW_T1: throttle 1 value out of range: %ld ", calcThrottle1);
+ }
faultHandler.raiseFault(POTACCELPEDAL, FAULT_THROTTLE_LOW_A, true);
- return false;
- }
+
+ throttleStatus = ERR_LOW_T1;
+ return false;
+ }
else
{
faultHandler.cancelOngoingFault(POTACCELPEDAL, FAULT_THROTTLE_LOW_A);
}
- if (config->numberPotMeters > 1) {
- calcThrottle2 = normalizeInput(rawSignal->input2, config->minimumLevel2, config->maximumLevel2);
-
- if (calcThrottle2 > (1000 + CFG_THROTTLE_TOLERANCE)) {
- if (status == OK)
- Logger::error(POTACCELPEDAL, "ERR_HIGH_T2: throttle 2 value out of range: %l", calcThrottle2);
- status = ERR_HIGH_T2;
+ if (config->numberPotMeters > 1) {
+ calcThrottle2 = normalizeInput(rawSignal->input2, config->minimumLevel2, config->maximumLevel2);
+
+ if (calcThrottle2 > (1000 + CFG_THROTTLE_TOLERANCE)) {
+ if (throttleStatus == OK) {
+ logger.error(this, "ERR_HIGH_T2: throttle 2 value out of range: %ld", calcThrottle2);
+ }
faultHandler.raiseFault(POTACCELPEDAL, FAULT_THROTTLE_HIGH_B, true);
- return false;
- }
+
+ throttleStatus = ERR_HIGH_T2;
+ return false;
+ }
else
{
faultHandler.cancelOngoingFault(POTACCELPEDAL, FAULT_THROTTLE_HIGH_B);
}
- if (calcThrottle2 < (0 - CFG_THROTTLE_TOLERANCE)) {
- if (status == OK)
- Logger::error(POTACCELPEDAL, "ERR_LOW_T2: throttle 2 value out of range: %l", calcThrottle2);
- status = ERR_LOW_T2;
+ if (calcThrottle2 < (0 - CFG_THROTTLE_TOLERANCE)) {
+ if (throttleStatus == OK) {
+ logger.error(this, "ERR_LOW_T2: throttle 2 value out of range: %ld", calcThrottle2);
+ }
faultHandler.cancelOngoingFault(POTACCELPEDAL, FAULT_THROTTLE_LOW_B);
- return false;
- }
+
+ throttleStatus = ERR_LOW_T2;
+ return false;
+ }
else
{
faultHandler.cancelOngoingFault(POTACCELPEDAL, FAULT_THROTTLE_LOW_B);
}
- if (config->throttleSubType == 2) {
- // inverted throttle 2 means the sum of the two throttles should be 1000
- if ( abs(1000 - calcThrottle1 - calcThrottle2) > ThrottleMaxErrValue) {
- if (status == OK)
- Logger::error(POTACCELPEDAL, "Sum of throttle 1 (%l) and throttle 2 (%l) exceeds max variance from 1000 (%l)",
- calcThrottle1, calcThrottle2, ThrottleMaxErrValue);
- status = ERR_MISMATCH;
+ if (config->throttleSubType == 2) {
+ // inverted throttle 2 means the sum of the two throttles should be 1000
+ if (abs(1000 - calcThrottle1 - calcThrottle2) > CFG_THROTTLE_MAX_ERROR) {
+ if (throttleStatus == OK)
+ logger.error(this, "Sum of throttle 1 (%ld) and throttle 2 (%ld) exceeds max variance from 1000 (%ld)",
+ calcThrottle1, calcThrottle2, CFG_THROTTLE_MAX_ERROR);
+
+ throttleStatus = ERR_MISMATCH;
faultHandler.raiseFault(POTACCELPEDAL, FAULT_THROTTLE_MISMATCH_AB, true);
- return false;
- }
+ return false;
+ }
else
{
faultHandler.cancelOngoingFault(POTACCELPEDAL, FAULT_THROTTLE_MISMATCH_AB);
}
- } else {
- if ((calcThrottle1 - ThrottleMaxErrValue) > calcThrottle2) { //then throttle1 is too large compared to 2
- if (status == OK)
- Logger::error(POTACCELPEDAL, "throttle 1 too high (%l) compared to 2 (%l)", calcThrottle1, calcThrottle2);
- status = ERR_MISMATCH;
+ } else {
+ if ((calcThrottle1 - CFG_THROTTLE_MAX_ERROR) > calcThrottle2) { //then throttle1 is too large compared to 2
+ if (throttleStatus == OK) {
+ logger.error(this, "throttle 1 too high (%ld) compared to 2 (%ld)", calcThrottle1, calcThrottle2);
+ }
+
+ throttleStatus = ERR_MISMATCH;
faultHandler.raiseFault(POTACCELPEDAL, FAULT_THROTTLE_MISMATCH_AB, true);
- return false;
- }
- else if ((calcThrottle2 - ThrottleMaxErrValue) > calcThrottle1) { //then throttle2 is too large compared to 1
- if (status == OK)
- Logger::error(POTACCELPEDAL, "throttle 2 too high (%l) compared to 1 (%l)", calcThrottle2, calcThrottle1);
- status = ERR_MISMATCH;
+ return false;
+ }
+
+ else if ((calcThrottle2 - CFG_THROTTLE_MAX_ERROR) > calcThrottle1) { //then throttle2 is too large compared to 1
+ if (throttleStatus == OK) {
+ logger.error(this, "throttle 2 too high (%ld) compared to 1 (%ld)", calcThrottle2, calcThrottle1);
+ }
faultHandler.raiseFault(POTACCELPEDAL, FAULT_THROTTLE_MISMATCH_AB, true);
- return false;
- }
- else
- {
+
+ throttleStatus = ERR_MISMATCH;
+ return false;
+ } else {
faultHandler.cancelOngoingFault(POTACCELPEDAL, FAULT_THROTTLE_MISMATCH_AB);
}
- }
- }
+ }
+ }
+
+ // all checks passed -> throttle is ok
+ if (throttleStatus != OK) {
+ logger.info(this, NORMAL_OPERATION);
+ }
- // all checks passed -> throttle is ok
- if (status != OK)
- Logger::info(POTACCELPEDAL, (char *)Constants::normalOperation);
- status = OK;
- return true;
+ throttleStatus = OK;
+ return true;
}
/*
* Convert the raw ADC values to a range from 0 to 1000 (per mille) according
* to the specified range and the type of potentiometer.
*/
-uint16_t PotThrottle::calculatePedalPosition(RawSignalData *rawSignal) {
- PotThrottleConfiguration *config = (PotThrottleConfiguration *) getConfiguration();
- uint16_t calcThrottle1, calcThrottle2;
+uint16_t PotThrottle::calculatePedalPosition(RawSignalData *rawSignal)
+{
+ PotThrottleConfiguration *config = (PotThrottleConfiguration *) getConfiguration();
+ uint16_t calcThrottle1, calcThrottle2;
- calcThrottle1 = normalizeInput(rawSignal->input1, config->minimumLevel1, config->maximumLevel1);
+ calcThrottle1 = normalizeInput(rawSignal->input1, config->minimumLevel, config->maximumLevel);
- if (config->numberPotMeters > 1) {
- calcThrottle2 = normalizeInput(rawSignal->input2, config->minimumLevel2, config->maximumLevel2);
- if (config->throttleSubType == 2) // inverted
- calcThrottle2 = 1000 - calcThrottle2;
- calcThrottle1 = (calcThrottle1 + calcThrottle2) / 2; // now the average of the two
- }
- return calcThrottle1;
+ if (config->numberPotMeters > 1) {
+ calcThrottle2 = normalizeInput(rawSignal->input2, config->minimumLevel2, config->maximumLevel2);
+
+ if (config->throttleSubType == 2) { // inverted
+ calcThrottle2 = 1000 - calcThrottle2;
+ }
+
+ calcThrottle1 = (calcThrottle1 + calcThrottle2) / 2; // now the average of the two
+ }
+
+ return calcThrottle1;
}
/*
* Return the device ID
*/
-DeviceId PotThrottle::getId() {
- return (POTACCELPEDAL);
+DeviceId PotThrottle::getId()
+{
+ return (POTACCELPEDAL);
}
/*
@@ -211,73 +230,68 @@ DeviceId PotThrottle::getId() {
* If possible values are read from EEPROM. If not, reasonable default values
* are chosen and the configuration is overwritten in the EEPROM.
*/
-void PotThrottle::loadConfiguration() {
- PotThrottleConfiguration *config = (PotThrottleConfiguration *) getConfiguration();
+void PotThrottle::loadConfiguration()
+{
+ PotThrottleConfiguration *config = (PotThrottleConfiguration *) getConfiguration();
- if (!config) { // as lowest sub-class make sure we have a config object
- config = new PotThrottleConfiguration();
- setConfiguration(config);
- }
+ if (!config) { // as lowest sub-class make sure we have a config object
+ config = new PotThrottleConfiguration();
+ setConfiguration(config);
+ }
- Throttle::loadConfiguration(); // call parent
+ Throttle::loadConfiguration(); // call parent
#ifdef USE_HARD_CODED
- if (false) {
+
+ if (false) {
#else
- if (prefsHandler->checksumValid()) { //checksum is good, read in the values stored in EEPROM
+
+ if (prefsHandler->checksumValid()) { //checksum is good, read in the values stored in EEPROM
#endif
- Logger::debug(POTACCELPEDAL, (char *)Constants::validChecksum);
- prefsHandler->read(EETH_MIN_ONE, &config->minimumLevel1);
- prefsHandler->read(EETH_MAX_ONE, &config->maximumLevel1);
- prefsHandler->read(EETH_MIN_TWO, &config->minimumLevel2);
- prefsHandler->read(EETH_MAX_TWO, &config->maximumLevel2);
- prefsHandler->read(EETH_NUM_THROTTLES, &config->numberPotMeters);
- prefsHandler->read(EETH_THROTTLE_TYPE, &config->throttleSubType);
- prefsHandler->read(EETH_ADC_1, &config->AdcPin1);
- prefsHandler->read(EETH_ADC_2, &config->AdcPin2);
-
- // ** This is potentially a condition that is only met if you don't have the EEPROM hardware **
- // If preferences have never been set before, numThrottlePots and throttleSubType
- // will both be zero. We really should refuse to operate in this condition and force
- // calibration, but for now at least allow calibration to work by setting numThrottlePots = 2
- if (config->numberPotMeters == 0 && config->throttleSubType == 0) {
- Logger::debug(POTACCELPEDAL, "THROTTLE APPEARS TO NEED CALIBRATION/DETECTION - choose 'z' on the serial console menu");
- config->numberPotMeters = 2;
- }
- } else { //checksum invalid. Reinitialize values and store to EEPROM
- Logger::warn(POTACCELPEDAL, (char *)Constants::invalidChecksum);
-
- config->minimumLevel1 = Throttle1MinValue;
- config->maximumLevel1 = Throttle1MaxValue;
- config->minimumLevel2 = Throttle2MinValue;
- config->maximumLevel2 = Throttle2MaxValue;
- config->numberPotMeters = ThrottleNumPots;
- config->throttleSubType = ThrottleSubtype;
- config->AdcPin1 = ThrottleADC1;
- config->AdcPin2 = ThrottleADC2;
-
- saveConfiguration();
- }
- Logger::debug(POTACCELPEDAL, "# of pots: %d subtype: %d", config->numberPotMeters, config->throttleSubType);
- Logger::debug(POTACCELPEDAL, "T1 MIN: %l MAX: %l T2 MIN: %l MAX: %l", config->minimumLevel1, config->maximumLevel1, config->minimumLevel2,
- config->maximumLevel2);
+ prefsHandler->read(EETH_LEVEL_MIN_TWO, &config->minimumLevel2);
+ prefsHandler->read(EETH_LEVEL_MAX_TWO, &config->maximumLevel2);
+ prefsHandler->read(EETH_NUM_THROTTLES, &config->numberPotMeters);
+ prefsHandler->read(EETH_THROTTLE_TYPE, &config->throttleSubType);
+ prefsHandler->read(EETH_ADC_1, &config->AdcPin1);
+ prefsHandler->read(EETH_ADC_2, &config->AdcPin2);
+
+ // ** This is potentially a condition that is only met if you don't have the EEPROM hardware **
+ // If preferences have never been set before, numThrottlePots and throttleSubType
+ // will both be zero. We really should refuse to operate in this condition and force
+ // calibration, but for now at least allow calibration to work by setting numThrottlePots = 2
+ if (config->numberPotMeters == 0 && config->throttleSubType == 0) {
+ logger.debug(this, "THROTTLE APPEARS TO NEED CALIBRATION/DETECTION - choose 'z' on the serial console menu");
+ config->numberPotMeters = 2;
+ }
+ } else { //checksum invalid. Reinitialize values and store to EEPROM
+ config->minimumLevel2 = 0;
+ config->maximumLevel2 = 0;
+ config->numberPotMeters = 1;
+ config->throttleSubType = 1;
+ config->AdcPin1 = 0;
+ config->AdcPin2 = 1;
+
+ saveConfiguration();
+ }
+
+ logger.info(this, "T2 MIN: %ld, T2 MAX: %ld", config->minimumLevel2, config->maximumLevel2);
+ logger.info(this, "# of pots: %d, subtype: %d", config->numberPotMeters, config->throttleSubType);
}
/*
* Store the current configuration to EEPROM
*/
-void PotThrottle::saveConfiguration() {
- PotThrottleConfiguration *config = (PotThrottleConfiguration *) getConfiguration();
-
- Throttle::saveConfiguration(); // call parent
-
- prefsHandler->write(EETH_MIN_ONE, config->minimumLevel1);
- prefsHandler->write(EETH_MAX_ONE, config->maximumLevel1);
- prefsHandler->write(EETH_MIN_TWO, config->minimumLevel2);
- prefsHandler->write(EETH_MAX_TWO, config->maximumLevel2);
- prefsHandler->write(EETH_NUM_THROTTLES, config->numberPotMeters);
- prefsHandler->write(EETH_THROTTLE_TYPE, config->throttleSubType);
- prefsHandler->write(EETH_ADC_1, config->AdcPin1);
- prefsHandler->write(EETH_ADC_2, config->AdcPin2);
- prefsHandler->saveChecksum();
+void PotThrottle::saveConfiguration()
+{
+ PotThrottleConfiguration *config = (PotThrottleConfiguration *) getConfiguration();
+
+ Throttle::saveConfiguration(); // call parent
+
+ prefsHandler->write(EETH_LEVEL_MIN_TWO, config->minimumLevel2);
+ prefsHandler->write(EETH_LEVEL_MAX_TWO, config->maximumLevel2);
+ prefsHandler->write(EETH_NUM_THROTTLES, config->numberPotMeters);
+ prefsHandler->write(EETH_THROTTLE_TYPE, config->throttleSubType);
+ prefsHandler->write(EETH_ADC_1, config->AdcPin1);
+ prefsHandler->write(EETH_ADC_2, config->AdcPin2);
+ prefsHandler->saveChecksum();
}
diff --git a/PotThrottle.h b/PotThrottle.h
index 194e9a5..49306ec 100644
--- a/PotThrottle.h
+++ b/PotThrottle.h
@@ -30,7 +30,7 @@
#include
#include "config.h"
#include "Throttle.h"
-#include "sys_io.h"
+#include "SystemIO.h"
#include "TickHandler.h"
#include "Logger.h"
#include "DeviceManager.h"
@@ -42,37 +42,39 @@
/*
* The extended configuration class with additional parameters for PotThrottle
*/
-class PotThrottleConfiguration: public ThrottleConfiguration {
+class PotThrottleConfiguration: public ThrottleConfiguration
+{
public:
- /*
- * Allows subclasses to have sub types for their pedal type
- * 0 - unknown type (prefs will return 0 if never set)
- * 1 - standard linear potentiometer (low-high). If 2 pots, both are low-high and the 2nd mirrors the 1st.
- * 2 - inverse potentiometer (high-low). If 2 pots, then 1st is low-high and 2nd is high-low)
- */
- uint8_t throttleSubType;
- uint16_t minimumLevel1, maximumLevel1, minimumLevel2, maximumLevel2; // values for when the pedal is at its min and max for each input
- uint8_t numberPotMeters; // the number of potentiometers to be used. Should support three as well since some pedals really do have that many
- uint8_t AdcPin1, AdcPin2; //which ADC pins to use for the throttle
+ /*
+ * Allows subclasses to have sub types for their pedal type
+ * 0 - unknown type (prefs will return 0 if never set)
+ * 1 - standard linear potentiometer (low-high). If 2 pots, both are low-high and the 2nd mirrors the 1st.
+ * 2 - inverse potentiometer (high-low). If 2 pots, then 1st is low-high and 2nd is high-low)
+ */
+ uint8_t throttleSubType;
+ uint16_t minimumLevel2, maximumLevel2; // values for when the pedal is at its min and max for secondary input
+ uint8_t numberPotMeters; // the number of potentiometers to be used. Should support three as well since some pedals really do have that many
+ uint8_t AdcPin1, AdcPin2; //which ADC pins to use for the throttle
};
-class PotThrottle: public Throttle {
+class PotThrottle: public Throttle
+{
public:
- PotThrottle();
- void setup();
- void handleTick();
- DeviceId getId();
- RawSignalData *acquireRawSignal();
+ PotThrottle();
+ void setup();
+ void handleTick();
+ DeviceId getId();
+ RawSignalData *acquireRawSignal();
- void loadConfiguration();
- void saveConfiguration();
+ void loadConfiguration();
+ void saveConfiguration();
protected:
- bool validateSignal(RawSignalData *);
- uint16_t calculatePedalPosition(RawSignalData *);
+ bool validateSignal(RawSignalData *);
+ uint16_t calculatePedalPosition(RawSignalData *);
private:
- RawSignalData rawSignal;
+ RawSignalData rawSignal;
};
#endif /* POT_THROTTLE_H_ */
diff --git a/PrefHandler.cpp b/PrefHandler.cpp
index 3bd3860..f408ccc 100644
--- a/PrefHandler.cpp
+++ b/PrefHandler.cpp
@@ -25,193 +25,251 @@ 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 "PrefHandler.h"
-PrefHandler::PrefHandler() {
- lkg_address = EE_MAIN_OFFSET; //default to normal mode
- base_address = 0;
+/*
+ * Each device must initialize its own PrefHandler with its ID.
+ * The device is looked up in the device table in the EEPROM and added if necessary.
+ */
+PrefHandler::PrefHandler(DeviceId id_in)
+{
+ uint16_t id;
+
+ deviceId = id_in;
+ enabled = false;
+ lkg_address = EE_MAIN_OFFSET;
+
+ initDeviceTable();
+
+ position = findDevice(deviceId);
+ if (position > -1) {
+ memCache.Read(EE_DEVICE_TABLE + (2 * position), &id);
+ if (id & 0x8000) {
+ enabled = true;
+ }
+ base_address = EE_DEVICES_BASE + (EE_DEVICE_SIZE * position);
+ logger.debug("Device ID %#x was found in device table at entry %i", (int) deviceId, position);
+ return;
+ }
+
+ //if we got here then there was no entry for this device in the table yet.
+ //try to find an empty spot and place it there.
+ position = findDevice(NEW);
+ if (position > -1) {
+ base_address = EE_DEVICES_BASE + (EE_DEVICE_SIZE * position);
+ lkg_address = EE_MAIN_OFFSET;
+ memCache.Write(EE_DEVICE_TABLE + (2 * position), (uint16_t)deviceId);
+ logger.debug("Device ID: %#x was placed into device table at entry: %i", (int) deviceId, position);
+ return;
+ }
+
+ //we found no matches and could not allocate a space. This is bad. Error out here
+ base_address = 0xF0F0;
+ logger.error("PrefManager - Device Table Full (Device ID: %#x) !!!", deviceId);
}
-bool PrefHandler::isEnabled()
+PrefHandler::~PrefHandler()
{
- return enabled;
}
-void PrefHandler::setEnabledStatus(bool en)
+/*
+ * Initialize the device table area in the eeprom if GEVCU marker is missing
+ */
+void PrefHandler::initDeviceTable()
{
- uint16_t id;
+ uint16_t id;
- enabled = en;
+ memCache.Read(EE_DEVICE_TABLE, &id);
+ if (id == EE_GEVCU_MARKER) { // the device table was properly initialized
+ return;
+ }
- if (enabled) {
- id |= 0x8000; //set enabled bit
- }
- else {
- id &= 0x7FFF; //clear enabled bit
- }
-
- memCache->Write(EE_DEVICE_TABLE + (2 * position), id);
-}
+ logger.debug("Initializing EEPROM device table");
+ //initialize table with zeros
+ id = 0;
+ for (int x = 1; x <= EE_NUM_DEVICES; x++) {
+ memCache.Write(EE_DEVICE_TABLE + (2 * x), id);
+ }
-void PrefHandler::initDevTable()
+ //write out magic entry
+ id = EE_GEVCU_MARKER;
+ memCache.Write(EE_DEVICE_TABLE, id);
+}
+
+/*
+ * Is the device enabled in the configuration
+ */
+bool PrefHandler::isEnabled()
{
- uint16_t id;
+ return enabled;
+}
- memCache->Read(EE_DEVICE_TABLE, &id);
- if (id == 0xDEAD) return;
+/*
+ * Enable / disable a device
+ */
+bool PrefHandler::setEnabled(bool en)
+{
+ uint16_t id = deviceId;
- Logger::debug("Initializing EEPROM device table");
+ enabled = en;
- //initialize table with zeros
- id = 0;
- for (int x = 1; x < 64; x++) {
- memCache->Write(EE_DEVICE_TABLE + (2 * x), id);
- }
+ if (enabled) {
+ id |= 0x8000; //set enabled bit
+ } else {
+ id &= 0x7FFF; //clear enabled bit
+ }
- //write out magic entry
- id = 0xDEAD;
- memCache->Write(EE_DEVICE_TABLE, id);
+ return memCache.Write(EE_DEVICE_TABLE + (2 * position), id);
}
-//Given a device ID we must search the 64 entry table found in EEPROM to see if the device
-//has a spot in EEPROM. If it does not then
-PrefHandler::PrefHandler(DeviceId id_in) {
- uint16_t id;
-
- enabled = false;
-
- initDevTable();
-
- for (int x = 1; x < 64; x++) {
- memCache->Read(EE_DEVICE_TABLE + (2 * x), &id);
- if ((id & 0x7FFF) == ((int)id_in)) {
- base_address = EE_DEVICES_BASE + (EE_DEVICE_SIZE * x);
- lkg_address = EE_MAIN_OFFSET;
- if (id & 0x8000) enabled = true;
- position = x;
- Logger::info("Device ID: %X was found in device table at entry: %i", (int)id_in, x);
- return;
- }
- }
+/*
+ * Search the device table for a device with a given ID
+ */
+int8_t PrefHandler::findDevice(DeviceId deviceId)
+{
+ uint16_t id;
- //if we got here then there was no entry for this device in the table yet.
- //try to find an empty spot and place it there.
- for (int x = 1; x < 64; x++) {
- memCache->Read(EE_DEVICE_TABLE + (2 * x), &id);
- if (id == 0) {
- base_address = EE_DEVICES_BASE + (EE_DEVICE_SIZE * x);
- lkg_address = EE_MAIN_OFFSET;
- enabled = false; //default to devices being off until the user says otherwise
- id = (int)id_in;
- memCache->Write(EE_DEVICE_TABLE + (2*x), id);
- position = x;
- Logger::info("Device ID: %X was placed into device table at entry: %i", (int)id, x);
- return;
- }
- }
+ for (int pos = 1; pos <= EE_NUM_DEVICES; pos++) {
+ memCache.Read(EE_DEVICE_TABLE + (2 * pos), &id);
- //we found no matches and could not allocate a space. This is bad. Error out here
- base_address = 0xF0F0;
- lkg_address = EE_MAIN_OFFSET;
- Logger::error("PrefManager - Device Table Full!!!");
+ if ((id & 0x7FFF) == deviceId) {
+ return pos;
+ }
+ }
+ return -1;
}
-//A special static function that can be called whenever, wherever to turn a specific device on/off. Does not
-//attempt to do so at runtime so the user will still have to power cycle to change the device status.
-//returns true if it could make the change, false if it could not.
-bool PrefHandler::setDeviceStatus(uint16_t device, bool enabled)
+/*
+ * Enable/Disable the LKG (last known good) configuration
+ */
+void PrefHandler::LKG_mode(bool mode)
{
- uint16_t id;
- for (int x = 1; x < 64; x++) {
- memCache->Read(EE_DEVICE_TABLE + (2 * x), &id);
- if ((id & 0x7FFF) == (device & 0x7FFF)) {
- Logger::debug("Found a device record to edit");
- if (enabled) {
- id |= 0x8000;
- }
- else {
- id &= 0x7FFF;
- }
- Logger::debug("ID to write: %X", id);
- memCache->Write(EE_DEVICE_TABLE + (2 * x), id);
- return true;
- }
- }
- return false;
-}
-
-PrefHandler::~PrefHandler() {
+ if (mode) {
+ lkg_address = EE_LKG_OFFSET;
+ } else {
+ lkg_address = EE_MAIN_OFFSET;
+ }
}
-void PrefHandler::LKG_mode(bool mode) {
- if (mode) lkg_address = EE_LKG_OFFSET;
- else lkg_address = EE_MAIN_OFFSET;
+/*
+ * Write one byte to an address relative to the device's base
+ */
+bool PrefHandler::write(uint16_t address, uint8_t val)
+{
+ if (address >= EE_DEVICE_SIZE) {
+ return false;
+ }
+ return memCache.Write((uint32_t) address + base_address + lkg_address, val);
}
-bool PrefHandler::write(uint16_t address, uint8_t val) {
- if (address >= EE_DEVICE_SIZE) return false;
- return memCache->Write((uint32_t)address + base_address + lkg_address, val);
+/*
+ * Write two bytes to n address relative to the device's base
+ */
+bool PrefHandler::write(uint16_t address, uint16_t val)
+{
+ if (address >= EE_DEVICE_SIZE) {
+ return false;
+ }
+ return memCache.Write((uint32_t) address + base_address + lkg_address, val);
}
-bool PrefHandler::write(uint16_t address, uint16_t val) {
- if (address >= EE_DEVICE_SIZE) return false;
- return memCache->Write((uint32_t)address + base_address + lkg_address, val);
+/*
+ * Write four bytes to an address relative to the device's base
+ */
+bool PrefHandler::write(uint16_t address, uint32_t val)
+{
+ if (address >= EE_DEVICE_SIZE) {
+ return false;
+ }
+ return memCache.Write((uint32_t) address + base_address + lkg_address, val);
}
-bool PrefHandler::write(uint16_t address, uint32_t val) {
- if (address >= EE_DEVICE_SIZE) return false;
- return memCache->Write((uint32_t)address + base_address + lkg_address, val);
+/*
+ * Read one byte from an address relative to the device's base
+ */
+bool PrefHandler::read(uint16_t address, uint8_t *val)
+{
+ if (address >= EE_DEVICE_SIZE) {
+ return false;
+ }
+ return memCache.Read((uint32_t) address + base_address + lkg_address, val);
}
-bool PrefHandler::read(uint16_t address, uint8_t *val) {
- if (address >= EE_DEVICE_SIZE) return false;
- return memCache->Read((uint32_t)address + base_address + lkg_address, val);
+/*
+ * Read two bytes from an address relative to the device's base
+ */
+bool PrefHandler::read(uint16_t address, uint16_t *val)
+{
+ if (address >= EE_DEVICE_SIZE) {
+ return false;
+ }
+ return memCache.Read((uint32_t) address + base_address + lkg_address, val);
}
-bool PrefHandler::read(uint16_t address, uint16_t *val) {
- if (address >= EE_DEVICE_SIZE) return false;
- return memCache->Read((uint32_t)address + base_address + lkg_address, val);
+/*
+ * Read four bytes from an address relative to the device's base
+ */
+bool PrefHandler::read(uint16_t address, uint32_t *val)
+{
+ if (address >= EE_DEVICE_SIZE) {
+ return false;
+ }
+ return memCache.Read((uint32_t) address + base_address + lkg_address, val);
}
-bool PrefHandler::read(uint16_t address, uint32_t *val) {
- if (address >= EE_DEVICE_SIZE) return false;
- return memCache->Read((uint32_t)address + base_address + lkg_address, val);
-}
+/*
+ * Calculate the checksum for a device configuration (block of EE_DEVICE_SIZE bytes)
+ */
+uint8_t PrefHandler::calcChecksum()
+{
+ uint16_t counter;
+ uint8_t accum = 0;
+ uint8_t temp;
-uint8_t PrefHandler::calcChecksum() {
- uint16_t counter;
- uint8_t accum = 0;
- uint8_t temp;
- for (counter = 1; counter < EE_DEVICE_SIZE; counter++) {
- memCache->Read((uint32_t)counter + base_address + lkg_address, &temp);
- accum += temp;
- }
- return accum;
-}
+ for (counter = 1; counter < EE_DEVICE_SIZE; counter++) {
+ memCache.Read((uint32_t) counter + base_address + lkg_address, &temp);
+ accum += temp;
+ }
-//calculate the current checksum and save it to the proper place
-void PrefHandler::saveChecksum() {
- uint8_t csum;
- csum = calcChecksum();
- memCache->Write(EE_CHECKSUM + base_address + lkg_address, csum);
+ return accum;
}
-bool PrefHandler::checksumValid() {
- //get checksum from EEPROM and calculate the current checksum to see if they match
- uint8_t stored_chk, calc_chk;
-
- memCache->Read(EE_CHECKSUM + base_address + lkg_address, &stored_chk);
- calc_chk = calcChecksum();
- Logger::info("Stored Checksum: %X Calc: %X", stored_chk, calc_chk);
-
- return (stored_chk == calc_chk);
+/*
+ * Calculate the current checksum and save it to the proper place within the device config (EE_CHECKSUM)
+ */
+void PrefHandler::saveChecksum()
+{
+ uint8_t csum;
+ csum = calcChecksum();
+ memCache.Write(EE_CHECKSUM + base_address + lkg_address, csum);
}
-void PrefHandler::forceCacheWrite()
+/*
+ * Get checksum from EEPROM and calculate the current checksum to see if they match
+ */
+bool PrefHandler::checksumValid()
{
- memCache->FlushAllPages();
+ uint8_t stored_chk, calc_chk;
+
+ memCache.Read(EE_CHECKSUM + base_address + lkg_address, &stored_chk);
+ calc_chk = calcChecksum();
+ if (stored_chk == calc_chk) {
+ logger.debug("%#x valid checksum, using stored config values", deviceId);
+ return true;
+ } else {
+ logger.warn("#x invalid checksum, using hard coded config values (stored: %#x, calc: %#x", deviceId, stored_chk, calc_chk);
+ return false;
+ }
}
+/*
+ * Write first dirty page of the cache to the eeprom
+ */
+void PrefHandler::suggestCacheWrite()
+{
+ // we don't call FlushAllPages because this would kill the timing (delay(10))
+ memCache.FlushSinglePage();
+}
diff --git a/PrefHandler.h b/PrefHandler.h
index d70f072..d5b2369 100644
--- a/PrefHandler.h
+++ b/PrefHandler.h
@@ -3,26 +3,26 @@
*
* header for preference handler
*
-Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
+ Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
-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:
+ 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 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.
+ 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.
*/
@@ -40,36 +40,40 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
#define PREF_MODE_NORMAL false
#define PREF_MODE_LKG true
-extern MemCache *memCache;
+#define SYSTEM_PROTO 1
+#define SYSTEM_DUED 2
+#define SYSTEM_GEVCU3 3
-class PrefHandler {
+class PrefHandler
+{
public:
- PrefHandler();
- PrefHandler(DeviceId id);
- ~PrefHandler();
- void LKG_mode(bool mode);
- bool write(uint16_t address, uint8_t val);
- bool write(uint16_t address, uint16_t val);
- bool write(uint16_t address, uint32_t val);
- bool read(uint16_t address, uint8_t *val);
- bool read(uint16_t address, uint16_t *val);
- bool read(uint16_t address, uint32_t *val);
- uint8_t calcChecksum();
- void saveChecksum();
- bool checksumValid();
- void forceCacheWrite();
- bool isEnabled();
- void setEnabledStatus(bool en);
- static bool setDeviceStatus(uint16_t device, bool enabled);
+ PrefHandler();
+ PrefHandler(DeviceId id);
+ ~PrefHandler();
+ void LKG_mode(bool mode);
+ bool write(uint16_t address, uint8_t val);
+ bool write(uint16_t address, uint16_t val);
+ bool write(uint16_t address, uint32_t val);
+ bool read(uint16_t address, uint8_t *val);
+ bool read(uint16_t address, uint16_t *val);
+ bool read(uint16_t address, uint32_t *val);
+ uint8_t calcChecksum();
+ void saveChecksum();
+ bool checksumValid();
+ void suggestCacheWrite();
+ bool isEnabled();
+ bool setEnabled(bool en);
private:
- uint32_t base_address; //base address for the parent device
- uint32_t lkg_address;
- bool use_lkg; //use last known good config?
- bool enabled;
- int position; //position within the device table
- void initDevTable();
+ DeviceId deviceId; // the device id the handler is assigned to
+ uint32_t base_address; //base address for the parent device
+ uint32_t lkg_address;
+ bool use_lkg; //use last known good config?
+ bool enabled;
+ int position; //position within the device table
+ void initDeviceTable();
+ static int8_t findDevice(DeviceId);
};
#endif
diff --git a/README.md b/README.md
index fa45819..26d4a5a 100644
--- a/README.md
+++ b/README.md
@@ -3,42 +3,32 @@ GEVCU
Generalized Electric Vehicle Control Unit
-Our website can be found at : http://www.gevcu.org
-
A project to create a fairly Arduino compatible ECU firmware
to interface with various electric vehicle hardware over canbus
(and possibly other comm channels)
-The project now builds in the Arduino IDE. So, use it to compile, send the firmware to the Arduino, and monitor serial. It all works very nicely.
-
-The master branch of this project is now switched to support the Due. The master branch is sparsely updated and only when the source tree is in stable shape.
-
-The older Macchina code has been moved to its own branch. This code is now *VERY* old but should work to control a DMOC645.
-
-ArduinoDue branch is more experimental than the master branch and includes the work of Michael Neuweiler.
+The project builds in the Arduino IDE. So, use it to compile, send the firmware to the Arduino, and monitor serial.
+It is suggested though to use the Eclipse based Arduino Plugin by Sloeber which provides far superior capabilities.
-The WIP branch is sync'd to EVTV's official changes and as such could be considered as a testing ground for the official source code distribution.
+The master branch of this project provides a stable code base. The main development happens on the development branch or feature branches if necessary.
+If the code on development branch is stable (end tested in practice by the developers), it is merged into the master branch.
You will need the following to have any hope of compiling and running the firmware:
-- A GEVCU board. Versions from 2 and up are supported.
-- Arduino IDE 1.5.4 - Do not use newer versions of the IDE
-- due_can library - There is a repo for this under Collin80
-- due_rtc library - Also under Collin80
-- due_wire library - once again
-- DueTimer library - and again
+- A GEVCU board. (Versions from 2 upward are supported)
+- THe latest Arduino IDE (or preferably Eclipse with ArduinoPlugin by Sloeber)
+- due_can library by Collin Kidder
+- due_wire library by Collin Kidder
+- DueTimer library by Collin Kidder
+- PID library by Brett Beauregard
All libraries belong in %USERPROFILE%\Documents\Arduino\libraries (Windows) or ~/Arduino/libraries (Linux/Mac).
You will need to remove -master or any other postfixes. Your library folders should be named as above.
-The canbus is supposed to be terminated on both ends of the bus. If you are testing with a DMOC and GEVCU then you've got two devices, each on opposing ends of the bus. So, both really should be terminated but for really short canbus lines you will probably get away with terminating just one side.
-
-If you are using a custom board then add a terminating resistor.
-
-If you are using the new prototype shield then it should already be terminated. The DMOC can be terminated by soldering a 120 ohm resistor between the canbus lines. I did this on my DMOC and hid the resistor inside the plug shroud.
+If you use a GEVCU 2.x, please change the pin assignments for CFG_EEPROM_WRITE_PROTECT and CFG_WIFI_RESET in config.h according to comment.
This software is MIT licensed:
-Copyright (c) 2014 Collin Kidder, Michael Neuweiler, Charles Galpin, Jack Rickard
+Copyright (c) 2014-2020 Collin Kidder, Michael Neuweiler, Charles Galpin, Jack Rickard
Permission is hereby granted, free of charge, to any person obtaining
a copy of this software and associated documentation files (the
@@ -58,4 +48,3 @@ 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.
-
diff --git a/SerialConsole.cpp b/SerialConsole.cpp
index 89b038b..9f3c572 100644
--- a/SerialConsole.cpp
+++ b/SerialConsole.cpp
@@ -26,706 +26,1104 @@
#include "SerialConsole.h"
-extern PrefHandler *sysPrefs;
+SerialConsole serialConsole;
-SerialConsole::SerialConsole(MemCache* memCache) :
- memCache(memCache), heartbeat(NULL) {
- init();
+SerialConsole::SerialConsole()
+{
+ handlingEvent = false;
+ ptrBuffer = 0;
+ state = STATE_ROOT_MENU;
}
-SerialConsole::SerialConsole(MemCache* memCache, Heartbeat* heartbeat) :
- memCache(memCache), heartbeat(heartbeat) {
- init();
+void SerialConsole::loop()
+{
+ if (handlingEvent == false) {
+ if (SerialUSB.available()) {
+ serialEvent();
+ }
+ }
+}
+
+void SerialConsole::printMenu()
+{
+ //Show build # here as well in case people are using the native port and don't get to see the start up messages
+ logger.console("\n%s (build: %d)", CFG_VERSION, CFG_BUILD_NUM);
+ logger.console("System State: %s", status.systemStateToStr(status.getSystemState()).c_str());
+ logger.console("System Menu:\n");
+ logger.console("Enable line endings of some sort (LF, CR, CRLF)\n");
+ logger.console("Short Commands:");
+ logger.console("h = help (displays this message)");
+ Device *heartbeat = deviceManager.getDeviceByID(HEARTBEAT);
+ if (heartbeat != NULL && heartbeat->isEnabled()) {
+ logger.console("L = show raw analog/digital input/output values (toggle)");
+ }
+ logger.console("K = set all outputs high");
+ logger.console("J = set all outputs low");
+ //logger.console("U,I = test EEPROM routines");
+ logger.console("z = detect throttle min/max, num throttles and subtype");
+ logger.console("Z = save throttle values");
+ logger.console("b = detect brake min/max");
+ logger.console("B = save brake values");
+ logger.console("p = enable wifi passthrough (reboot required to resume normal operation)");
+ logger.console("S = show list of devices");
+ logger.console("w = reset wifi to factory defaults, setup GEVCU ad-hoc network");
+ logger.console("W = activate wifi WPS mode for pairing");
+ logger.console("s = Scan WiFi for nearby access points");
+ logger.console("P = perform pre-charge measurement");
+
+ logger.console("\nConfig Commands (enter command=newvalue)\n");
+ logger.console("LOGLEVEL=[deviceId,]%d - set log level (0=debug, 1=info, 2=warn, 3=error, 4=off)", logger.getLogLevel());
+ logger.console("SYSTYPE=%d - Set board revision (Dued=2, GEVCU3=3, GEVCU4=4)", systemIO.getSystemType());
+ logger.console("WLAN - send a AT+i command to the wlan device");
+ logger.console("NUKE=1 - Resets all device settings in EEPROM. You have been warned.");
+ logger.console("KILL=... - kill a device temporarily (until reboot)\n");
+
+ deviceManager.printDeviceList();
+
+ printMenuMotorController();
+ printMenuThrottle();
+ printMenuBrake();
+ printMenuSystemIO();
+ printMenuCharger();
+ printMenuDcDcConverter();
+ printMenuCanOBD2();
+}
+
+void SerialConsole::printMenuMotorController()
+{
+ MotorController* motorController = (MotorController*) deviceManager.getMotorController();
+
+ if (motorController && motorController->getConfiguration()) {
+ MotorControllerConfiguration *config = (MotorControllerConfiguration *) motorController->getConfiguration();
+ logger.console("\nMOTOR CONTROLS\n");
+ logger.console("TORQ=%d - Set torque upper limit (in 0.1Nm)", config->torqueMax);
+ logger.console("RPMS=%d - Set maximum speed (in RPMs)", config->speedMax);
+ logger.console("MOMODE=%d - Set power mode (0=torque, 1=speed, default=0)", config->powerMode);
+ logger.console("CRLVL=%d - Torque to use for creep (0=disable) (in 1%%)", config->creepLevel);
+ logger.console("CRSPD=%d - maximal speed until creep is applied (in RPMs)", config->creepSpeed);
+ logger.console("REVLIM=%d - How much torque to allow in reverse (in 0.1%%)", config->reversePercent);
+ logger.console("MOINVD=%d - invert the direction of the motor (0=normal, 1=invert)", config->invertDirection);
+ logger.console("MOSLEWM=%d - slew rate for motoring (in 0.1 percent/sec, 0=disabled)", config->slewRateMotor);
+ logger.console("MOSLEWR=%d - slew rate for regen (in 0.1 percent/sec, 0=disabled)", config->slewRateRegen);
+ logger.console("MOMWMX=%d - maximal mechanical power of motor (in 100W steps)", config->maxMechanicalPowerMotor);
+ logger.console("MORWMX=%d - maximal mechanical power of regen (in 100W steps)", config->maxMechanicalPowerRegen);
+ logger.console("MOBRHD=%d - percentage of max torque to apply for brake hold (in 1%%)", config->brakeHold);
+ logger.console("MOBRHQ=%d - coefficient for brake hold, the higher the smoother brake hold force will be applied (1-255, 10=default)", config->brakeHoldForceCoefficient);
+ logger.console("NOMV=%d - Fully charged pack voltage that automatically resets the kWh counter (in 0.1V)", config->nominalVolt);
+ logger.console("CRUISEP=%f - Kp value for cruise control (default 1.0, entered as 1000)", config->cruiseKp);
+ logger.console("CRUISEI=%f - Ki value for cruise control (default 0.2, entered as 200)", config->cruiseKi);
+ logger.console("CRUISED=%f - Kd value for cruise control (default 0.1, enteres as 100)", config->cruiseKd);
+ logger.console("CRUISEL=%d - Delta in rpm/kph to actual speed while pressing +/- button > 1sec (default 500)", config->cruiseLongPressDelta);
+ logger.console("CRUISES=%d - Delta in rpm/kph to target speed when pressing +/- button < 1 sec (default 300)", config->cruiseStepDelta);
+ logger.console("CRUISER=%d - use rpm or vehicle speed to control cruise speed (default 1, 1=rpm/0=speed)", config->cruiseUseRpm);
+ if (motorController->getId() == BRUSA_DMC5) {
+ BrusaDMC5Configuration *dmc5Config = (BrusaDMC5Configuration *) config;
+ logger.console("MOMVMN=%d - minimum DC voltage limit for motoring (in 0.1V)", dmc5Config->dcVoltLimitMotor);
+ logger.console("MOMCMX=%d - current limit for motoring (in 0.1A)", dmc5Config->dcCurrentLimitMotor);
+ logger.console("MORVMX=%d - maximum DC voltage limit for regen (in 0.1V)", dmc5Config->dcVoltLimitRegen);
+ logger.console("MORCMX=%d - current limit for regen (in 0.1A)", dmc5Config->dcCurrentLimitRegen);
+ logger.console("MOOSC=%d - enable the DMC5 oscillation limiter (1=enable, 0=disable, also set DMC parameter!)",
+ dmc5Config->enableOscillationLimiter);
+ }
+ }
}
-void SerialConsole::init() {
- handlingEvent = false;
+PowerMode powerMode;
+
+
+void SerialConsole::printMenuThrottle()
+{
+ Throttle *accelerator = deviceManager.getAccelerator();
- //State variables for serial console
- ptrBuffer = 0;
- state = STATE_ROOT_MENU;
- loopcount=0;
- cancel=false;
-
+ if (accelerator && accelerator->getConfiguration()) {
+ ThrottleConfiguration *config = (ThrottleConfiguration *) accelerator->getConfiguration();
+ logger.console("\nTHROTTLE CONTROLS\n");
+ if (accelerator->getId() == POTACCELPEDAL) {
+ PotThrottleConfiguration *potConfig = (PotThrottleConfiguration *) config;
+ logger.console("TPOT=%d - Number of pots to use (1 or 2)", potConfig->numberPotMeters);
+ logger.console("TTYPE=%d - Set throttle subtype (1=std linear, 2=inverse)", potConfig->throttleSubType);
+ logger.console("T1MN=%d - Set throttle 1 min value", potConfig->minimumLevel);
+ logger.console("T1MX=%d - Set throttle 1 max value", potConfig->maximumLevel);
+ logger.console("T1ADC=%d - Set throttle 1 ADC pin", potConfig->AdcPin1);
+ logger.console("T2MN=%d - Set throttle 2 min value", potConfig->minimumLevel2);
+ logger.console("T2MX=%d - Set throttle 2 max value", potConfig->maximumLevel2);
+ logger.console("T2ADC=%d - Set throttle 2 ADC pin", potConfig->AdcPin2);
+ }
+ if (accelerator->getId() == CANACCELPEDAL) {
+ CanThrottleConfiguration *canConfig = (CanThrottleConfiguration *) config;
+ logger.console("T1MN=%d - Set throttle 1 min value", canConfig->minimumLevel);
+ logger.console("T1MX=%d - Set throttle 1 max value", canConfig->maximumLevel);
+ }
+ logger.console("TRGNMAX=%d - Pedal position where regen is at max (in 0.1%%)", config->positionRegenMaximum);
+ logger.console("TRGNMIN=%d - Pedal position where regen is at min (in 0.1%%)", config->positionRegenMinimum);
+ logger.console("TFWD=%d - Pedal position where forward motion starts (in 0.1%%)", config->positionForwardMotionStart);
+ logger.console("TMAP=%d - Pedal position of 50%% torque (in 0.1%%)", config->positionHalfPower);
+ logger.console("TMINRN=%d - Torque to use for min throttle regen (in 1%%)", config->minimumRegen);
+ logger.console("TMAXRN=%d - Torque to use for max throttle regen (in 1%%)", config->maximumRegen);
+ }
}
-void SerialConsole::loop() {
- if(!cancel)
- {
- if(loopcount++==350000){
- //DeviceManager::getInstance()->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_CONFIG_CHANGE, NULL);
- DeviceManager::getInstance()->updateWifi();
- cancel=true;
+void SerialConsole::printMenuBrake()
+{
+ Throttle *brake = deviceManager.getBrake();
+
+ if (brake && brake->getConfiguration()) {
+ ThrottleConfiguration *config = (ThrottleConfiguration *) brake->getConfiguration();
+ logger.console("\nBRAKE CONTROLS\n");
+ if (brake->getId() == POTBRAKEPEDAL) {
+ PotBrakeConfiguration *potConfig = (PotBrakeConfiguration *) config;
+ logger.console("B1ADC=%d - Set brake ADC pin", potConfig->AdcPin1);
}
- }
- if (handlingEvent == false) {
- if (SerialUSB.available()) {
- serialEvent();
- }
- }
+ logger.console("B1MN=%d - Set brake min value", config->minimumLevel);
+ logger.console("B1MX=%d - Set brake max value", config->maximumLevel);
+ logger.console("BMINR=%d - Torque for start of brake regen (in 1%%)", config->minimumRegen);
+ logger.console("BMAXR=%d - Torque for maximum brake regen (in 1%%)", config->maximumRegen);
+ }
}
-void SerialConsole::printMenu() {
- MotorController* motorController = (MotorController*) DeviceManager::getInstance()->getMotorController();
- Throttle *accelerator = DeviceManager::getInstance()->getAccelerator();
- Throttle *brake = DeviceManager::getInstance()->getBrake();
- ICHIPWIFI *wifi = (ICHIPWIFI*) DeviceManager::getInstance()->getDeviceByType(DEVICE_WIFI);
-
- //Show build # here as well in case people are using the native port and don't get to see the start up messages
- SerialUSB.print("Build number: ");
- SerialUSB.println(CFG_BUILD_NUM);
- if (motorController) {
- SerialUSB.println(
- "Motor Controller Status: isRunning: " + String(motorController->isRunning()) + " isFaulted: " + String(motorController->isFaulted()));
- }
- SerialUSB.println("System Menu:");
- SerialUSB.println();
- SerialUSB.println("Enable line endings of some sort (LF, CR, CRLF)");
- SerialUSB.println();
- SerialUSB.println("Short Commands:");
- SerialUSB.println("h = help (displays this message)");
- if (heartbeat != NULL) {
- SerialUSB.println("L = show raw analog/digital input/output values (toggle)");
- }
- SerialUSB.println("K = set all outputs high");
- SerialUSB.println("J = set all outputs low");
- //SerialUSB.println("U,I = test EEPROM routines");
- SerialUSB.println("E = dump system eeprom values");
- SerialUSB.println("z = detect throttle min/max, num throttles and subtype");
- SerialUSB.println("Z = save throttle values");
- SerialUSB.println("b = detect brake min/max");
- SerialUSB.println("B = save brake values");
- SerialUSB.println("p = enable wifi passthrough (reboot required to resume normal operation)");
- SerialUSB.println("S = show possible device IDs");
- SerialUSB.println("w = GEVCU 4.2 reset wifi to factory defaults, setup GEVCU ad-hoc network");
- SerialUSB.println("W = GEVCU 5.2 reset wifi to factory defaults, setup GEVCU as 10.0.0.1 Access Point");
- SerialUSB.println("s = Scan WiFi for nearby access points");
- SerialUSB.println();
- SerialUSB.println("Config Commands (enter command=newvalue). Current values shown in parenthesis:");
- SerialUSB.println();
- Logger::console("LOGLEVEL=%i - set log level (0=debug, 1=info, 2=warn, 3=error, 4=off)", Logger::getLogLevel());
-
- uint8_t systype;
- sysPrefs->read(EESYS_SYSTEM_TYPE, &systype);
- Logger::console("SYSTYPE=%i - Set board revision (Dued=2, GEVCU3=3, GEVCU4=4)", systype);
-
- DeviceManager::getInstance()->printDeviceList();
-
- if (motorController && motorController->getConfiguration()) {
- MotorControllerConfiguration *config = (MotorControllerConfiguration *) motorController->getConfiguration();
-
- SerialUSB.println();
- SerialUSB.println("MOTOR CONTROLS");
- SerialUSB.println();
- Logger::console("TORQ=%i - Set torque upper limit (tenths of a Nm)", config->torqueMax);
- Logger::console("RPM=%i - Set maximum RPM", config->speedMax);
- Logger::console("REVLIM=%i - How much torque to allow in reverse (Tenths of a percent)", config->reversePercent);
-
- Logger::console("COOLFAN=%i - Digital output to turn on cooling fan(0-7, 255 for none)", config->coolFan);
- Logger::console("COOLON=%i - Inverter temperature C to turn cooling on", config->coolOn);
- Logger::console("COOLOFF=%i - Inverter temperature C to turn cooling off", config->coolOff);
- Logger::console("BRAKELT = %i - Digital output to turn on brakelight (0-7, 255 for none)", config->brakeLight);
- Logger::console("REVLT=%i - Digital output to turn on reverse light (0-7, 255 for none)", config->revLight);
- Logger::console("ENABLEIN=%i - Digital input to enable motor controller (0-3, 255 for none)", config->enableIn);
- Logger::console("REVIN=%i - Digital input to reverse motor rotation (0-3, 255 for none)", config->reverseIn);
-
- }
-
-
- if (accelerator && accelerator->getConfiguration()) {
- PotThrottleConfiguration *config = (PotThrottleConfiguration *) accelerator->getConfiguration();
- SerialUSB.println();
- SerialUSB.println("THROTTLE CONTROLS");
- SerialUSB.println();
-
- Logger::console("TPOT=%i - Number of pots to use (1 or 2)", config->numberPotMeters);
- Logger::console("TTYPE=%i - Set throttle subtype (1=std linear, 2=inverse)", config->throttleSubType);
- Logger::console("T1ADC=%i - Set throttle 1 ADC pin", config->AdcPin1);
- Logger::console("T1MN=%i - Set throttle 1 min value", config->minimumLevel1);
- Logger::console("T1MX=%i - Set throttle 1 max value", config->maximumLevel1);
- Logger::console("T2ADC=%i - Set throttle 2 ADC pin", config->AdcPin2);
- Logger::console("T2MN=%i - Set throttle 2 min value", config->minimumLevel2);
- Logger::console("T2MX=%i - Set throttle 2 max value", config->maximumLevel2);
- Logger::console("TRGNMAX=%i - Tenths of a percent of pedal where regen is at max", config->positionRegenMaximum);
- Logger::console("TRGNMIN=%i - Tenths of a percent of pedal where regen is at min", config->positionRegenMinimum);
- Logger::console("TFWD=%i - Tenths of a percent of pedal where forward motion starts", config->positionForwardMotionStart);
- Logger::console("TMAP=%i - Tenths of a percent of pedal where 50% throttle will be", config->positionHalfPower);
- Logger::console("TMINRN=%i - Percent of full torque to use for min throttle regen", config->minimumRegen);
- Logger::console("TMAXRN=%i - Percent of full torque to use for max throttle regen", config->maximumRegen);
- Logger::console("TCREEP=%i - Percent of full torque to use for creep (0=disable)", config->creep);
- }
-
- if (brake && brake->getConfiguration()) {
- PotThrottleConfiguration *config = (PotThrottleConfiguration *) brake->getConfiguration();
- SerialUSB.println();
- SerialUSB.println("BRAKE CONTROLS");
- SerialUSB.println();
-
- Logger::console("B1ADC=%i - Set brake ADC pin", config->AdcPin1);
- Logger::console("B1MN=%i - Set brake min value", config->minimumLevel1);
- Logger::console("B1MX=%i - Set brake max value", config->maximumLevel1);
- Logger::console("BMINR=%i - Percent of full torque for start of brake regen", config->minimumRegen);
- Logger::console("BMAXR=%i - Percent of full torque for maximum brake regen", config->maximumRegen);
- }
-
- if (motorController && motorController->getConfiguration()) {
- MotorControllerConfiguration *config = (MotorControllerConfiguration *) motorController->getConfiguration();
- SerialUSB.println();
- SerialUSB.println("PRECHARGE CONTROLS");
- SerialUSB.println();
-
- Logger::console("PREDELAY=%i - Precharge delay time in milliseconds ", config->prechargeR);
- Logger::console("PRELAY=%i - Which output to use for precharge contactor (255 to disable)", config->prechargeRelay);
- Logger::console("MRELAY=%i - Which output to use for main contactor (255 to disable)", config->mainContactorRelay);
- SerialUSB.println();
- SerialUSB.println("WIRELESS LAN COMMANDS");
- SerialUSB.println();
- Logger::console("WIREACH=anycommand - sends ATi+anycommand to WiReach Module");
- Logger::console("SSID=anyname - sets broadcast ID to anyname");
- Logger::console("IP=192.168.3.10 - sets IP of website to whatever IP is entered");
- Logger::console("PWD=secret - sets website configuration password to entered string");
- Logger::console("CHANNEL=4 - sets website wireless channel - 1 to 11");
- Logger::console("SECURITY=password - sets website wireless connection security for WPA2-AES and password");
-
- SerialUSB.println();
- SerialUSB.println("OTHER");
- SerialUSB.println();
-
- Logger::console("NOMV=%i - Fully charged pack voltage that automatically resets kWh counter", config->nominalVolt/10);
- Logger::console("kWh=%d - kiloWatt Hours of energy used", config->kilowattHrs/3600000);
- Logger::console("OUTPUT=<0-7> - toggles state of specified digital output");
- Logger::console("NUKE=1 - Resets all device settings in EEPROM. You have been warned.");
-
- }
-
-
+void SerialConsole::printMenuSystemIO()
+{
+ SystemIOConfiguration *config = systemIO.getConfiguration();
+
+ if (config) {
+ logger.console("\nSYSTEM I/O\n");
+ logger.console("CTP=%d - Set car type (0=OBD2 compatible, 1=Volvo S80, 2=Volvo V50)", config->carType);
+ logger.console("ENABLEI=%d - Digital input to use for enable signal (255 to disable)", config->enableInput);
+ logger.console("CHARGEI=%d - Digital input to use for charger signal (255 to disable)", config->chargePowerAvailableInput);
+ logger.console("INTERLI=%d - Digital input to use for interlock signal (255 to disable)", config->interlockInput);
+ logger.console("REVIN=%d - Digital input to reverse motor rotation (255 to disable)\n", config->reverseInput);
+ logger.console("ABSIN=%d - Digital input to indicate active ABS system (255 to disable)\n", config->absInput);
+ logger.console("GEARIN=%d - Digital input to indicate active gear change (255 to disable)\n", config->gearChangeInput);
+
+ logger.console("PREDELAY=%d - Precharge delay time (in milliseconds)", config->prechargeMillis);
+ logger.console("PRELAY=%d - Digital output to use for precharge contactor (255 to disable)", config->prechargeRelayOutput);
+ logger.console("MRELAY=%d - Digital output to use for main contactor (255 to disable)", config->mainContactorOutput);
+ logger.console("NRELAY=%d - Digital output to use for secondary contactor (255 to disable)", config->secondaryContactorOutput);
+ logger.console("FRELAY=%d - Digital output to use for fast charge contactor (255 to disable)\n", config->fastChargeContactorOutput);
+
+ logger.console("ENABLEM=%d - Digital output to use for enable motor signal (255 to disable)", config->enableMotorOutput);
+ logger.console("ENABLEC=%d - Digital output to use for enable charger signal (255 to disable)", config->enableChargerOutput);
+ logger.console("ENABLED=%d - Digital output to use for enable dc-dc converter signal (255 to disable)", config->enableDcDcOutput);
+ logger.console("ENABLEH=%d - Digital output to use for enable heater signal (255 to disable)\n", config->enableHeaterOutput);
+ logger.console("HEATERON=%d - external temperature below which heater is turned on (0 - 40 deg C, 255 = ignore)", config->heaterTemperatureOn);
+
+ logger.console("HEATVALV=%d - Digital output to actuate heater valve (255 to disable)", config->heaterValveOutput);
+ logger.console("HEATPUMP=%d - Digital output to turn on heater pump (255 to disable)", config->heaterPumpOutput);
+ logger.console("COOLPUMP=%d - Digital output to turn on cooling pump (255 to disable)", config->coolingPumpOutput);
+ logger.console("COOLFAN=%d - Digital output to turn on cooling fan (255 to disable)", config->coolingFanOutput);
+ logger.console("COOLON=%d - Controller temperature to turn cooling on (deg celsius)", config->coolingTempOn);
+ logger.console("COOLOFF=%d - Controller temperature to turn cooling off (deg celsius)\n", config->coolingTempOff);
+
+ logger.console("BRAKELT=%d - Digital output to use for brake light (255 to disable)", config->brakeLightOutput);
+ logger.console("REVLT=%d - Digital output to use for reverse light (255 to disable)", config->reverseLightOutput);
+ logger.console("PWRSTR=%d - Digital output to use to enable power steering (255 to disable)", config->powerSteeringOutput);
+// logger.console("TBD=%d - Digital output to use to xxxxxx (255 to disable)", config->unusedOutput);
+
+ logger.console("WARNLT=%d - Digital output to use for reverse light (255 to disable)", config->warningOutput);
+ logger.console("LIMITLT=%d - Digital output to use for limitation indicator (255 to disable)", config->powerLimitationOutput);
+ logger.console("SOCHG=%d - Analog output to use to indicate state of charge (255 to disable)", config->stateOfChargeOutput);
+ logger.console("STLGT=%d - Analog output to use to indicate system status (255 to disable)", config->statusLightOutput);
+ logger.console("OUTPUT=<0-7> - toggles state of specified digital output");
+ }
+}
+
+void SerialConsole::printMenuCharger()
+{
+ Charger *charger = deviceManager.getCharger();
+
+ if (charger && charger->getConfiguration()) {
+ ChargerConfiguration *config = (ChargerConfiguration *) charger->getConfiguration();
+ logger.console("\nCHARGER CONTROLS\n");
+ logger.console("CHCC=%d - Constant current (in 0.1A)", config->constantCurrent);
+ logger.console("CHCV=%d - Constant voltage (in 0.1V)", config->constantVoltage);
+ logger.console("CHTC=%d - Terminate current (in 0.1A)", config->terminateCurrent);
+ logger.console("CHICMX=%d - Maximum input current (in 0.1A)", config->maximumInputCurrent);
+ logger.console("CHICIN=%d - Initial input current (in 0.1A)", config->initialInputCurrent);
+ logger.console("CHBVMN=%d - Minimum battery voltage (in 0.1V)", config->minimumBatteryVoltage);
+ logger.console("CHBVMX=%d - Maximum battery voltage (in 0.1V)", config->maximumBatteryVoltage);
+ logger.console("CHTPMN=%d - Minimum battery temperature for charging (in 0.1 deg C)", config->minimumTemperature);
+ logger.console("CHTPMX=%d - Maximum battery temperature for charging (in 0.1 deg C)", config->maximumTemperature);
+ logger.console("CHAHMX=%d - Maximum ampere hours (in 0.1Ah)", config->maximumAmpereHours);
+ logger.console("CHCTMX=%d - Maximum charge time (in 1 min)", config->maximumChargeTime);
+ logger.console("CHTDRC=%d - Derating of charge current (in 0.1A per deg C)", config->deratingRate);
+ logger.console("CHTDRS=%d - Reference temperature for derating (in 0.1 deg C)", config->deratingReferenceTemperature);
+ logger.console("CHTHYS=%d - Hysterese temperature where charging will be stopped (in 0.1 deg C)", config->hystereseStopTemperature);
+ logger.console("CHTHYR=%d - Hysterese temperature where charging will resume (in 0.1 deg C)", config->hystereseResumeTemperature);
+ logger.console("CHMT=%d - Input voltage measurement time (in ms)", config->measureTime);
+ logger.console("CHMC=%d - Input voltage measurement current (in 0.1 A)", config->measureCurrent);
+ logger.console("CHVD=%d - Input voltage drop factor (V / CHVD = allowed voltage drop)", config->voltageDrop);
+ }
+}
+
+void SerialConsole::printMenuDcDcConverter()
+{
+ DcDcConverter *dcDcConverter = deviceManager.getDcDcConverter();
+
+ if (dcDcConverter && dcDcConverter->getConfiguration()) {
+ DcDcConverterConfiguration *config = (DcDcConverterConfiguration *) dcDcConverter->getConfiguration();
+ logger.console("\nDCDC CONVERTER CONTROLS\n");
+ logger.console("DCMODE=%d - operation mode (0 = buck/default, 1 = boost)", config->mode);
+ logger.console("DCBULV=%d - Buck mode LV voltage (in 0.1V)", config->lowVoltageCommand);
+ logger.console("DCBULVC=%d - Buck mode LV current limit (in 1A)", config->lvBuckModeCurrentLimit);
+ logger.console("DCBUHVV=%d - Buck mode HV under voltage limit (in 1 V)", config->hvUndervoltageLimit);
+ logger.console("DCBUHVC=%d - Buck mode HV current limit (in 0.1A)", config->hvBuckModeCurrentLimit);
+ logger.console("DCBOHV=%d - Boost mode HV voltage (in 1V)", config->highVoltageCommand);
+ logger.console("DCBOLVV=%d - Boost mode LV under voltage limit (in 0.1V)", config->lvUndervoltageLimit);
+ logger.console("DCBOLVC=%d - Boost mode LV current limit (in 1A)", config->lvBoostModeCurrentLinit);
+ logger.console("DCBOHVC=%d - Boost mode HV current limit (in 0.1A)", config->hvBoostModeCurrentLimit);
+ if (dcDcConverter->getId() == BRUSA_BSC6) {
+ BrusaBSC6Configuration *bscConfig = (BrusaBSC6Configuration *) config;
+ logger.console("DCDBG=%d - Enable debug mode of BSC6 (0=off,1=on)", bscConfig->debugMode);
+ }
+ }
+}
+
+void SerialConsole::printMenuCanOBD2()
+{
+ CanOBD2 *canObd2 = (CanOBD2 *)deviceManager.getDeviceByID(CANOBD2);
+
+ if (canObd2 && canObd2->isEnabled() && canObd2->getConfiguration()) {
+ CanOBD2Configuration *config = (CanOBD2Configuration *) canObd2->getConfiguration();
+ logger.console("\nCAN OBD2 CONTROLS\n");
+ logger.console("ODBRES=%d - can bus number on which to respond to ODB2 PID requests (0=EV bus, 1=car bus, default=0)", config->canBusRespond);
+ logger.console("ODBRESO=%d - offset to can ID 0x7e8 to respond to OBD2 PID requests (0-7, default=0)", config->canIdOffsetRespond);
+ logger.console("OBDPOL=%d - can bus number on which we poll data from the car (0=EV, 1=car, default=1)", config->canBusPoll);
+ logger.console("OBDPOLO=%d - offset to can ID 0x7e0 to request ODB2 data (0-7, 255=broadcast, default = 255)", config->canIdOffsetPoll);
+ }
}
-/* There is a help menu (press H or h or ?)
+/* There is a help menu (press H or h or ?)
This is no longer going to be a simple single character console.
Now the system can handle up to 80 input characters. Commands are submitted
by sending line ending (LF, CR, or both)
*/
-void SerialConsole::serialEvent() {
- int incoming;
- incoming = SerialUSB.read();
- if (incoming == -1) { //false alarm....
- return;
- }
-
- if (incoming == 10 || incoming == 13) { //command done. Parse it.
- handleConsoleCmd();
- ptrBuffer = 0; //reset line counter once the line has been processed
- } else {
- cmdBuffer[ptrBuffer++] = (unsigned char) incoming;
- if (ptrBuffer > 79)
- ptrBuffer = 79;
- }
+void SerialConsole::serialEvent()
+{
+ int incoming;
+ incoming = SerialUSB.read();
+
+ if (incoming == -1) { //false alarm....
+ return;
+ }
+
+ if (incoming == 10 || incoming == 13) { //command done. Parse it.
+ handleConsoleCmd();
+ ptrBuffer = 0; //reset line counter once the line has been processed
+ } else {
+ cmdBuffer[ptrBuffer++] = (unsigned char) incoming;
+
+ if (ptrBuffer > 79) {
+ ptrBuffer = 79;
+ }
+ }
}
-void SerialConsole::handleConsoleCmd() {
- handlingEvent = true;
-
- if (state == STATE_ROOT_MENU) {
- if (ptrBuffer == 1) { //command is a single ascii character
- handleShortCmd();
- } else { //if cmd over 1 char then assume (for now) that it is a config line
- handleConfigCmd();
- }
- }
- handlingEvent = false;
+void SerialConsole::handleConsoleCmd()
+{
+ handlingEvent = true;
+
+ if (state == STATE_ROOT_MENU) {
+ if (ptrBuffer == 1) { //command is a single ascii character
+ handleShortCmd();
+ } else { //if cmd over 1 char then assume (for now) that it is a config line
+ handleCmd();
+ }
+ }
+
+ handlingEvent = false;
}
/*For simplicity the configuration setting code uses four characters for each configuration choice. This makes things easier for
comparison purposes.
*/
-void SerialConsole::handleConfigCmd() {
- PotThrottleConfiguration *acceleratorConfig = NULL;
- PotThrottleConfiguration *brakeConfig = NULL;
- MotorControllerConfiguration *motorConfig = NULL;
- Throttle *accelerator = DeviceManager::getInstance()->getAccelerator();
- Throttle *brake = DeviceManager::getInstance()->getBrake();
- MotorController *motorController = DeviceManager::getInstance()->getMotorController();
- int i;
- int newValue;
- bool updateWifi = true;
-
- //Logger::debug("Cmd size: %i", ptrBuffer);
- if (ptrBuffer < 6)
- return; //4 digit command, =, value is at least 6 characters
- cmdBuffer[ptrBuffer] = 0; //make sure to null terminate
- String cmdString = String();
- unsigned char whichEntry = '0';
- i = 0;
-
- while (cmdBuffer[i] != '=' && i < ptrBuffer) {
- cmdString.concat(String(cmdBuffer[i++]));
- }
- i++; //skip the =
- if (i >= ptrBuffer)
- {
- Logger::console("Command needs a value..ie TORQ=3000");
- Logger::console("");
- return; //or, we could use this to display the parameter instead of setting
- }
-
- if (accelerator)
- acceleratorConfig = (PotThrottleConfiguration *) accelerator->getConfiguration();
- if (brake)
- brakeConfig = (PotThrottleConfiguration *) brake->getConfiguration();
- if (motorController)
- motorConfig = (MotorControllerConfiguration *) motorController->getConfiguration();
-
- // strtol() is able to parse also hex values (e.g. a string "0xCAFE"), useful for enable/disable by device id
- newValue = strtol((char *) (cmdBuffer + i), NULL, 0);
-
- cmdString.toUpperCase();
- if (cmdString == String("TORQ") && motorConfig) {
- Logger::console("Setting Torque Limit to %i", newValue);
- motorConfig->torqueMax = newValue;
- motorController->saveConfiguration();
- } else if (cmdString == String("RPM") && motorConfig) {
- Logger::console("Setting RPM Limit to %i", newValue);
- motorConfig->speedMax = newValue;
- motorController->saveConfiguration();
- } else if (cmdString == String("REVLIM") && motorConfig) {
- Logger::console("Setting Reverse Limit to %i", newValue);
- motorConfig->reversePercent = newValue;
- motorController->saveConfiguration();
- } else if (cmdString == String("TPOT") && acceleratorConfig) {
- Logger::console("Setting # of Throttle Pots to %i", newValue);
- acceleratorConfig->numberPotMeters = newValue;
- accelerator->saveConfiguration();
- } else if (cmdString == String("TTYPE") && acceleratorConfig) {
- Logger::console("Setting Throttle Subtype to %i", newValue);
- acceleratorConfig->throttleSubType = newValue;
- accelerator->saveConfiguration();
- } else if (cmdString == String("T1ADC") && acceleratorConfig) {
- Logger::console("Setting Throttle1 ADC pin to %i", newValue);
- acceleratorConfig->AdcPin1 = newValue;
- accelerator->saveConfiguration();
- } else if (cmdString == String("T1MN") && acceleratorConfig) {
- Logger::console("Setting Throttle1 Min to %i", newValue);
- acceleratorConfig->minimumLevel1 = newValue;
- accelerator->saveConfiguration();
- } else if (cmdString == String("T1MX") && acceleratorConfig) {
- Logger::console("Setting Throttle1 Max to %i", newValue);
- acceleratorConfig->maximumLevel1 = newValue;
- accelerator->saveConfiguration();
- }
- else if (cmdString == String("T2ADC") && acceleratorConfig) {
- Logger::console("Setting Throttle2 ADC pin to %i", newValue);
- acceleratorConfig->AdcPin2 = newValue;
- accelerator->saveConfiguration();
- } else if (cmdString == String("T2MN") && acceleratorConfig) {
- Logger::console("Setting Throttle2 Min to %i", newValue);
- acceleratorConfig->minimumLevel2 = newValue;
- accelerator->saveConfiguration();
- } else if (cmdString == String("T2MX") && acceleratorConfig) {
- Logger::console("Setting Throttle2 Max to %i", newValue);
- acceleratorConfig->maximumLevel2 = newValue;
- accelerator->saveConfiguration();
- } else if (cmdString == String("TRGNMAX") && acceleratorConfig) {
- Logger::console("Setting Throttle Regen maximum to %i", newValue);
- acceleratorConfig->positionRegenMaximum = newValue;
- accelerator->saveConfiguration();
- } else if (cmdString == String("TRGNMIN") && acceleratorConfig) {
- Logger::console("Setting Throttle Regen minimum to %i", newValue);
- acceleratorConfig->positionRegenMinimum = newValue;
- accelerator->saveConfiguration();
- } else if (cmdString == String("TFWD") && acceleratorConfig) {
- Logger::console("Setting Throttle Forward Start to %i", newValue);
- acceleratorConfig->positionForwardMotionStart = newValue;
- accelerator->saveConfiguration();
- } else if (cmdString == String("TMAP") && acceleratorConfig) {
- Logger::console("Setting Throttle MAP Point to %i", newValue);
- acceleratorConfig->positionHalfPower = newValue;
- accelerator->saveConfiguration();
- } else if (cmdString == String("TMINRN") && acceleratorConfig) {
- Logger::console("Setting Throttle Regen Minimum Strength to %i", newValue);
- acceleratorConfig->minimumRegen = newValue;
- accelerator->saveConfiguration();
- } else if (cmdString == String("TMAXRN") && acceleratorConfig) {
- Logger::console("Setting Throttle Regen Maximum Strength to %i", newValue);
- acceleratorConfig->maximumRegen = newValue;
- accelerator->saveConfiguration();
- } else if (cmdString == String("TCREEP") && acceleratorConfig) {
- Logger::console("Setting Throttle Creep Strength to %i", newValue);
- acceleratorConfig->creep = newValue;
- accelerator->saveConfiguration();
- } else if (cmdString == String("BMAXR") && brakeConfig) {
- Logger::console("Setting Max Brake Regen to %i", newValue);
- brakeConfig->maximumRegen = newValue;
- brake->saveConfiguration();
- } else if (cmdString == String("BMINR") && brakeConfig) {
- Logger::console("Setting Min Brake Regen to %i", newValue);
- brakeConfig->minimumRegen = newValue;
- brake->saveConfiguration();
- }
- else if (cmdString == String("B1ADC") && acceleratorConfig) {
- Logger::console("Setting Brake ADC pin to %i", newValue);
- brakeConfig->AdcPin1 = newValue;
- accelerator->saveConfiguration();
- } else if (cmdString == String("B1MX") && brakeConfig) {
- Logger::console("Setting Brake Max to %i", newValue);
- brakeConfig->maximumLevel1 = newValue;
- brake->saveConfiguration();
- } else if (cmdString == String("B1MN") && brakeConfig) {
- Logger::console("Setting Brake Min to %i", newValue);
- brakeConfig->minimumLevel1 = newValue;
- brake->saveConfiguration();
- } else if (cmdString == String("PREC") && motorConfig) {
- Logger::console("Setting Precharge Capacitance to %i", newValue);
- motorConfig->kilowattHrs = newValue;
- motorController->saveConfiguration();
- } else if (cmdString == String("PREDELAY") && motorConfig) {
- Logger::console("Setting Precharge Time Delay to %i milliseconds", newValue);
- motorConfig->prechargeR = newValue;
- motorController->saveConfiguration();
- } else if (cmdString == String("NOMV") && motorConfig) {
- Logger::console("Setting fully charged voltage to %d vdc", newValue);
- motorConfig->nominalVolt = newValue * 10;
- motorController->saveConfiguration();
- } else if (cmdString == String("BRAKELT") && motorConfig) {
- motorConfig->brakeLight = newValue;
- motorController->saveConfiguration();
- Logger::console("Brake light output set to DOUT%i.",newValue);
- } else if (cmdString == String("REVLT") && motorConfig) {
- motorConfig->revLight = newValue;
- motorController->saveConfiguration();
- Logger::console("Reverse light output set to DOUT%i.",newValue);
- } else if (cmdString == String("ENABLEIN") && motorConfig) {
- motorConfig->enableIn = newValue;
- motorController->saveConfiguration();
- Logger::console("Motor Enable input set to DIN%i.",newValue);
- } else if (cmdString == String("REVIN") && motorConfig) {
- motorConfig->reverseIn = newValue;
- motorController->saveConfiguration();
- Logger::console("Motor Reverse input set to DIN%i.",newValue);
- } else if (cmdString == String("MRELAY") && motorConfig) {
- Logger::console("Setting Main Contactor relay output to DOUT%i", newValue);
- motorConfig->mainContactorRelay = newValue;
- motorController->saveConfiguration();
- } else if (cmdString == String("PRELAY") && motorConfig) {
- Logger::console("Setting Precharge Relay output to DOUT%i", newValue);
- motorConfig->prechargeRelay = newValue;
- motorController->saveConfiguration();
- } else if (cmdString == String("ENABLE")) {
- if (PrefHandler::setDeviceStatus(newValue, true)) {
- sysPrefs->forceCacheWrite(); //just in case someone takes us literally and power cycles quickly
- Logger::console("Successfully enabled device.(%X, %d) Power cycle to activate.", newValue, newValue);
- }
- else {
- Logger::console("Invalid device ID (%X, %d)", newValue, newValue);
- }
- } else if (cmdString == String("DISABLE")) {
- if (PrefHandler::setDeviceStatus(newValue, false)) {
- sysPrefs->forceCacheWrite(); //just in case someone takes us literally and power cycles quickly
- Logger::console("Successfully disabled device. Power cycle to deactivate.");
- }
- else {
- Logger::console("Invalid device ID (%X, %d)", newValue, newValue);
- }
- } else if (cmdString == String("SYSTYPE")) {
- if (newValue < 5 && newValue > 0) {
- sysPrefs->write(EESYS_SYSTEM_TYPE, (uint8_t)(newValue));
- sysPrefs->saveChecksum();
- sysPrefs->forceCacheWrite(); //just in case someone takes us literally and power cycles quickly
- Logger::console("System type updated. Power cycle to apply.");
- }
- else Logger::console("Invalid system type. Please enter a value 1 - 4");
-
-
- } else if (cmdString == String("LOGLEVEL")) {
- switch (newValue) {
- case 0:
- Logger::setLoglevel(Logger::Debug);
- Logger::console("setting loglevel to 'debug'");
- break;
- case 1:
- Logger::setLoglevel(Logger::Info);
- Logger::console("setting loglevel to 'info'");
- break;
- case 2:
- Logger::console("setting loglevel to 'warning'");
- Logger::setLoglevel(Logger::Warn);
- break;
- case 3:
- Logger::console("setting loglevel to 'error'");
- Logger::setLoglevel(Logger::Error);
- break;
- case 4:
- Logger::console("setting loglevel to 'off'");
- Logger::setLoglevel(Logger::Off);
- break;
- }
- sysPrefs->write(EESYS_LOG_LEVEL, (uint8_t)newValue);
- sysPrefs->saveChecksum();
-
- } else if (cmdString == String("WIREACH")) {
- DeviceManager::getInstance()->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)(cmdBuffer + i));
- Logger::info("sent \"AT+i%s\" to WiReach wireless LAN device", (cmdBuffer + i));
- DeviceManager::getInstance()->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)"DOWN");
- updateWifi = false;
- } else if (cmdString == String("SSID")) {
- String cmdString = String();
- cmdString.concat("WLSI");
- cmdString.concat('=');
- cmdString.concat((char *)(cmdBuffer + i));
- Logger::info("Sent \"%s\" to WiReach wireless LAN device", (cmdString.c_str()));
- DeviceManager::getInstance()->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)cmdString.c_str());
- DeviceManager::getInstance()->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)"DOWN");
- updateWifi = false;
- } else if (cmdString == String("IP")) {
- String cmdString = String();
- cmdString.concat("DIP");
- cmdString.concat('=');
- cmdString.concat((char *)(cmdBuffer + i));
- Logger::info("Sent \"%s\" to WiReach wireless LAN device", (cmdString.c_str()));
- DeviceManager::getInstance()->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)cmdString.c_str());
- DeviceManager::getInstance()->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)"DOWN");
- updateWifi = false;
- } else if (cmdString == String("CHANNEL")) {
- String cmdString = String();
- cmdString.concat("WLCH");
- cmdString.concat('=');
- cmdString.concat((char *)(cmdBuffer + i));
- Logger::info("Sent \"%s\" to WiReach wireless LAN device", (cmdString.c_str()));
- DeviceManager::getInstance()->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)cmdString.c_str());
- DeviceManager::getInstance()->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)"DOWN");
- updateWifi = false;
- } else if (cmdString == String("SECURITY")) {
- String cmdString = String();
- cmdString.concat("WLPP");
- cmdString.concat('=');
- cmdString.concat((char *)(cmdBuffer + i));
- Logger::info("Sent \"%s\" to WiReach wireless LAN device", (cmdString.c_str()));
- DeviceManager::getInstance()->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)cmdString.c_str());
- DeviceManager::getInstance()->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)"DOWN");
- updateWifi = false;
-
- } else if (cmdString == String("PWD")) {
- String cmdString = String();
- cmdString.concat("WPWD");
- cmdString.concat('=');
- cmdString.concat((char *)(cmdBuffer + i));
- Logger::info("Sent \"%s\" to WiReach wireless LAN device", (cmdString.c_str()));
- DeviceManager::getInstance()->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)cmdString.c_str());
- DeviceManager::getInstance()->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)"DOWN");
- updateWifi = false;
-
- } else if (cmdString == String("COOLFAN") && motorConfig) {
- Logger::console("Cooling fan output updated to: %i", newValue);
- motorConfig->coolFan = newValue;
- motorController->saveConfiguration();
- } else if (cmdString == String("COOLON")&& motorConfig) {
- if (newValue <= 200 && newValue >= 0) {
- Logger::console("Cooling fan ON temperature updated to: %i degrees", newValue);
- motorConfig->coolOn = newValue;
- motorController->saveConfiguration();
- }
- else Logger::console("Invalid cooling ON temperature. Please enter a value 0 - 200F");
- } else if (cmdString == String("COOLOFF")&& motorConfig) {
- if (newValue <= 200 && newValue >= 0) {
- Logger::console("Cooling fan OFF temperature updated to: %i degrees", newValue);
- motorConfig->coolOff = newValue;
- motorController->saveConfiguration();
- }
- else Logger::console("Invalid cooling OFF temperature. Please enter a value 0 - 200F");
- } else if (cmdString == String("OUTPUT") && newValue<8) {
- int outie = getOutput(newValue);
- Logger::console("DOUT%d, STATE: %d",newValue, outie);
- if(outie)
- {
- setOutput(newValue,0);
- motorController->statusBitfield1 &= ~(1 << newValue);//Clear
- }
- else
- {
- setOutput(newValue,1);
- motorController->statusBitfield1 |=1 << newValue;//setbit to Turn on annunciator
- }
-
-
- Logger::console("DOUT0:%d, DOUT1:%d, DOUT2:%d, DOUT3:%d, DOUT4:%d, DOUT5:%d, DOUT6:%d, DOUT7:%d", getOutput(0), getOutput(1), getOutput(2), getOutput(3), getOutput(4), getOutput(5), getOutput(6), getOutput(7));
- } else if (cmdString == String("NUKE")) {
- if (newValue == 1)
- { //write zero to the checksum location of every device in the table.
- //Logger::console("Start of EEPROM Nuke");
- uint8_t zeroVal = 0;
- for (int j = 0; j < 64; j++)
- {
- memCache->Write(EE_DEVICES_BASE + (EE_DEVICE_SIZE * j), zeroVal);
- memCache->FlushAllPages();
- }
- Logger::console("Device settings have been nuked. Reboot to reload default settings");
- }
- } else {
- Logger::console("Unknown command");
- updateWifi = false;
- }
- // send updates to ichip wifi
- if (updateWifi)
- DeviceManager::getInstance()->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_CONFIG_CHANGE, NULL);
+void SerialConsole::handleCmd()
+{
+ int i;
+ int value;
+ bool updateWifi = true;
+
+ //logger.debug("Cmd size: %d", ptrBuffer);
+ if (ptrBuffer < 6) {
+ return; //4 digit command, =, value is at least 6 characters
+ }
+
+ cmdBuffer[ptrBuffer] = 0; //make sure to null terminate
+ String command = String();
+ i = 0;
+
+ while (cmdBuffer[i] != '=' && i < ptrBuffer) {
+ /*if (cmdBuffer[i] >= '0' && cmdBuffer[i] <= '9') {
+ whichEntry = cmdBuffer[i++] - '0';
+ }
+ else */command.concat(String(cmdBuffer[i++]));
+ }
+
+ i++; //skip the =
+
+ if (i >= ptrBuffer) {
+ logger.console("Command needs a value..ie TORQ=3000\n");
+ return; //or, we could use this to display the parameter instead of setting
+ }
+
+ // strtol() is able to parse also hex values (e.g. a string "0xCAFE"), useful for enable/disable by device id
+ value = strtol((char *) (cmdBuffer + i), NULL, 0);
+ command.toUpperCase();
+
+ if (!handleConfigCmdMotorController(command, value) && !handleConfigCmdThrottle(command, value) && !handleConfigCmdBrake(command, value)
+ && !handleConfigCmdSystemIO(command, value) && !handleConfigCmdCharger(command, value) && !handleConfigCmdDcDcConverter(command, value)
+ && !handleConfigCmdSystem(command, value, (cmdBuffer + i))) {
+ if (handleConfigCmdWifi(command, (cmdBuffer + i))) {
+ updateWifi = false;
+ } else {
+ logger.warn("unknown command: %s", command.c_str());
+ }
+ }
+
+ // send updates to ichip wifi
+ if (updateWifi) {
+ deviceManager.sendMessage(DEVICE_WIFI, ICHIP2128, MSG_CONFIG_CHANGE, NULL);
+ }
+}
+
+bool SerialConsole::handleConfigCmdMotorController(String command, long value)
+{
+ MotorController *motorController = deviceManager.getMotorController();
+ MotorControllerConfiguration *config = NULL;
+
+ if (!motorController) {
+ return false;
+ }
+ config = (MotorControllerConfiguration *) motorController->getConfiguration();
+
+ if (command == String("TORQ")) {
+ value = constrain(value, 0, 1000000);
+ logger.console("Setting torque limit to %fNm", value / 10.0f);
+ config->torqueMax = value;
+ } else if (command == String("RPMS")) {
+ value = constrain(value, 0, 1000000);
+ logger.console("Setting speed limit to %drpm", value);
+ config->speedMax = value;
+ } else if (command == String("MOMODE")) {
+ value = constrain(value, 0, 1);
+ logger.console("Setting power mode to %s", (value == 0 ? "torque" : "speed (be careful !!)"));
+ config->powerMode = (PowerMode)value;
+ } else if (command == String("CRLVL")) {
+ value = constrain(value, 0, 100);
+ logger.console("Setting creep level to %d%%", value);
+ config->creepLevel = value;
+ } else if (command == String("CRSPD")) {
+ value = constrain(value, 0, config->speedMax);
+ logger.console("Setting creep speed to %drpm", value);
+ config->creepSpeed = value;
+ } else if (command == String("REVLIM")) {
+ value = constrain(value, 0, 1000);
+ logger.console("Setting reverse limit to %f%%", value / 10.0f);
+ config->reversePercent = value;
+ } else if (command == String("NOMV")) {
+ value = constrain(value, 0, 100000);
+ logger.console("Setting fully charged voltage to %fV", value / 10.0f);
+ config->nominalVolt = value;
+ } else if (command == String("MOINVD")) {
+ value = constrain(value, 0, 1);
+ logger.console("Setting motor direction to %s", (value ? "inverted" : "normal"));
+ config->invertDirection = value;
+ } else if (command == String("MOSLEWM")) {
+ logger.console("Setting slew rate motoring to %f percent/sec", value / 10.0f);
+ config->slewRateMotor = value;
+ } else if (command == String("MOSLEWR")) {
+ logger.console("Setting slew regen rate to %f percent/sec", value / 10.0f);
+ config->slewRateRegen = value;
+ } else if (command == String("MOMWMX")) {
+ logger.console("Setting maximal mechanical power of motor to %fkW", value / 10.0f);
+ config->maxMechanicalPowerMotor = value;
+ } else if (command == String("MORWMX")) {
+ logger.console("Setting maximal mechanical power of regen to %fkW", value / 10.0f);
+ config->maxMechanicalPowerRegen = value;
+ } else if (command == String("MOBRHD")) {
+ logger.console("Setting maximal brake hold level to %d%%", value);
+ config->brakeHold = value;
+ } else if (command == String("MOBRHQ")) {
+ value = constrain(value, 1, 255);
+ logger.console("Setting brake hold force coefficient to %d", value);
+ config->brakeHoldForceCoefficient = value;
+ } else if (command == String("MOMVMN") && (motorController->getId() == BRUSA_DMC5)) {
+ logger.console("Setting minimum DC voltage limit for motoring to %fV", value / 10.0f);
+ ((BrusaDMC5Configuration *) config)->dcVoltLimitMotor = value;
+ } else if (command == String("MOMCMX") && (motorController->getId() == BRUSA_DMC5)) {
+ logger.console("Setting current limit for motoring to %fA", value / 10.0f);
+ ((BrusaDMC5Configuration *) config)->dcCurrentLimitMotor = value;
+ } else if (command == String("MORVMX") && (motorController->getId() == BRUSA_DMC5)) {
+ logger.console("Setting maximum DC voltage limit for regen to %fV", value / 10.0f);
+ ((BrusaDMC5Configuration *) config)->dcVoltLimitRegen = value;
+ } else if (command == String("MORCMX") && (motorController->getId() == BRUSA_DMC5)) {
+ logger.console("Setting current limit for regen to %fA", value / 10.0f);
+ ((BrusaDMC5Configuration *) config)->dcCurrentLimitRegen = value;
+ } else if (command == String("MOOSC") && (motorController->getId() == BRUSA_DMC5)) {
+ value = constrain(value, 0, 1);
+ logger.console("Setting oscillation limiter to %s", (value == 0 ? "disabled" : "enabled"));
+ ((BrusaDMC5Configuration *) config)->enableOscillationLimiter = value;
+ } else if (command == String("CRUISEP")) {
+ logger.console("Setting cruise control Kp value to %f", value / 1000.0f);
+ config->cruiseKp = value / 1000.0f;
+ } else if (command == String("CRUISEI")) {
+ logger.console("Setting cruise control Ki value to %f", value / 1000.0f);
+ config->cruiseKi = value / 1000.0f;
+ } else if (command == String("CRUISED")) {
+ logger.console("Setting cruise control Kd value to %f", value / 1000.0f);
+ config->cruiseKd = value / 1000.0f;
+ } else if (command == String("CRUISEL")) {
+ value = constrain(value, 1, 9000);
+ logger.console("Setting delta in rpm/kph to actual speed to %d", value);
+ config->cruiseLongPressDelta = value;
+ } else if (command == String("CRUISES")) {
+ value = constrain(value, 1, 9000);
+ logger.console("Setting delta in rpm/kph to target speed to %d", value);
+ config->cruiseStepDelta = value;
+ } else if (command == String("CRUISER")) {
+ value = constrain(value, 0, 1);
+ logger.console("Setting cruise control method to '%s'", (value == 1 ? "rpm" : "vehicle speed"));
+ config->cruiseUseRpm = value;
+ } else {
+ return false;
+ }
+ motorController->saveConfiguration();
+ return true;
+}
+
+bool SerialConsole::handleConfigCmdThrottle(String command, long value)
+{
+ Throttle *throttle = deviceManager.getAccelerator();
+ ThrottleConfiguration *config = NULL;
+
+ if (!throttle) {
+ return false;
+ }
+ config = (ThrottleConfiguration *) throttle->getConfiguration();
+
+ if (command == String("TPOT") && (throttle->getId() == POTACCELPEDAL)) {
+ value = constrain(value, 1, 3);
+ logger.console("Setting # of throttle pots to %d", value);
+ ((PotThrottleConfiguration *) config)->numberPotMeters = value;
+ } else if (command == String("TTYPE") && (throttle->getId() == POTACCELPEDAL)) {
+ value = constrain(value, 1, 2);
+ logger.console("Setting throttle subtype to %s", (value == 2 ? "inverse" : "std linear"));
+ ((PotThrottleConfiguration *) config)->throttleSubType = value;
+ } else if (command == String("T1ADC") && (throttle->getId() == POTACCELPEDAL)) {
+ logger.console("Setting Throttle1 ADC pin to %d", value);
+ ((PotThrottleConfiguration *) config)->AdcPin1 = value;
+ } else if (command == String("T2ADC") && (throttle->getId() == POTACCELPEDAL)) {
+ logger.console("Setting Throttle2 ADC pin to %d", value);
+ ((PotThrottleConfiguration *) config)->AdcPin2 = value;
+ } else if (command == String("T2MN") && (throttle->getId() == POTACCELPEDAL)) {
+ logger.console("Setting throttle 2 min to %d", value);
+ ((PotThrottleConfiguration *) config)->minimumLevel2 = value;
+ } else if (command == String("T2MX") && (throttle->getId() == POTACCELPEDAL)) {
+ logger.console("Setting throttle 2 max to %d", value);
+ ((PotThrottleConfiguration *) config)->maximumLevel2 = value;
+ } else if (command == String("T1MN")) {
+ logger.console("Setting throttle 1 min to %d", value);
+ config->minimumLevel = value;
+ } else if (command == String("T1MX")) {
+ logger.console("Setting throttle 1 max to %d", value);
+ config->maximumLevel = value;
+ } else if (command == String("TRGNMAX")) {
+ value = constrain(value, 0, config->positionRegenMinimum);
+ logger.console("Setting throttle regen maximum to %f%%", value / 10.0f);
+ config->positionRegenMaximum = value;
+ } else if (command == String("TRGNMIN")) {
+ value = constrain(value, config->positionRegenMaximum, config->positionForwardMotionStart);
+ logger.console("Setting throttle regen minimum to %f%%", value / 10.0f);
+ config->positionRegenMinimum = value;
+ } else if (command == String("TFWD")) {
+ value = constrain(value, config->positionRegenMinimum, config->positionHalfPower);
+ logger.console("Setting throttle forward start to %f%%", value / 10.0f);
+ config->positionForwardMotionStart = value;
+ } else if (command == String("TMAP")) {
+ value = constrain(value, config->positionForwardMotionStart, 1000);
+ logger.console("Setting throttle 50%% torque to %f%%", value / 10.0f);
+ config->positionHalfPower = value;
+ } else if (command == String("TMINRN")) {
+ value = constrain(value, 0, config->maximumRegen);
+ logger.console("Setting throttle regen minimum strength to %d%%", value);
+ config->minimumRegen = value;
+ } else if (command == String("TMAXRN")) {
+ value = constrain(value, config->minimumRegen, 100);
+ logger.console("Setting throttle Regen maximum strength to %d%%", value);
+ config->maximumRegen = value;
+ } else {
+ return false;
+ }
+ throttle->saveConfiguration();
+ return true;
+}
+
+bool SerialConsole::handleConfigCmdBrake(String command, long value)
+{
+ Throttle *brake = deviceManager.getBrake();
+ ThrottleConfiguration *config = NULL;
+
+ if (!brake) {
+ return false;
+ }
+ config = (ThrottleConfiguration *) brake->getConfiguration();
+
+ if (command == String("B1MN")) {
+ logger.console("Setting brake min to %d", value);
+ config->minimumLevel = value;
+ } else if (command == String("B1MX")) {
+ logger.console("Setting brake max to %d", value);
+ config->maximumLevel = value;
+ } else if (command == String("BMINR")) {
+ value = constrain(value, 0, config->maximumRegen);
+ logger.console("Setting min brake regen to %d%%", value);
+ config->minimumRegen = value;
+ } else if (command == String("BMAXR")) {
+ value = constrain(value, config->minimumRegen, 100);
+ logger.console("Setting max brake regen to %d%%", value);
+ config->maximumRegen = value;
+ } else if (command == String("B1ADC") && (brake->getId() == POTBRAKEPEDAL)) {
+ logger.console("Setting Brake ADC pin to %d", value);
+ ((PotBrakeConfiguration *) config)->AdcPin1 = value;
+ } else {
+ return false;
+ }
+ brake->saveConfiguration();
+ return true;
+}
+
+bool SerialConsole::handleConfigCmdSystemIO(String command, long value)
+{
+ SystemIOConfiguration *config = systemIO.getConfiguration();
+
+ if (command == String("CTP")) {
+ logger.console("Setting car type to %d", value);
+ config->carType = (SystemIOConfiguration::CarType) value;
+ } else if (command == String("ENABLEI")) {
+ if (value <= CFG_NUMBER_DIGITAL_INPUTS && value >= 0) {
+ logger.console("Setting enable signal to input %d.", value);
+ config->enableInput = value;
+ } else {
+ logger.console("Invalid enable signal input number. Please enter a value 0 - %d", CFG_NUMBER_DIGITAL_INPUTS - 1);
+ }
+ } else if (command == String("CHARGEI")) {
+ value = constrain(value, 0, 255);
+ logger.console("Setting charge signal to input %d", value);
+ config->chargePowerAvailableInput = value;
+ } else if (command == String("INTERLI")) {
+ value = constrain(value, 0, 255);
+ logger.console("Setting interlock signal to input %d", value);
+ config->interlockInput = value;
+ } else if (command == String("REVIN")) {
+ config->reverseInput = value;
+ logger.console("Motor reverse signal set to input %d.", value);
+ } else if (command == String("ABSIN")) {
+ config->absInput = value;
+ logger.console("ABS signal set to input %d.", value);
+ } else if (command == String("GEARIN")) {
+ config->gearChangeInput = value;
+ logger.console("Gear change signal set to input %d.", value);
+ } else if (command == String("PREDELAY")) {
+ value = constrain(value, 0, 100000);
+ logger.console("Setting precharge time to %dms", value);
+ config->prechargeMillis = value;
+ } else if (command == String("PRELAY")) {
+ value = constrain(value, 0, 255);
+ logger.console("Setting precharge relay to output %d", value);
+ config->prechargeRelayOutput = value;
+ } else if (command == String("MRELAY")) {
+ value = constrain(value, 0, 255);
+ logger.console("Setting main contactor to output %d", value);
+ config->mainContactorOutput = value;
+ } else if (command == String("NRELAY")) {
+ value = constrain(value, 0, 255);
+ logger.console("Setting secondary contactor to output %d", value);
+ config->secondaryContactorOutput = value;
+ } else if (command == String("FRELAY")) {
+ value = constrain(value, 0, 255);
+ logger.console("Setting fast charge contactor to output %d", value);
+ config->fastChargeContactorOutput = value;
+ } else if (command == String("ENABLEM")) {
+ value = constrain(value, 0, 255);
+ logger.console("Setting enable motor signal to output %d", value);
+ config->enableMotorOutput = value;
+ } else if (command == String("ENABLEC")) {
+ value = constrain(value, 0, 255);
+ logger.console("Setting enable charger signal to output %d", value);
+ config->enableChargerOutput = value;
+ } else if (command == String("ENABLED")) {
+ value = constrain(value, 0, 255);
+ logger.console("Setting enable DC-DC converter signal to output %d", value);
+ config->enableDcDcOutput = value;
+ } else if (command == String("ENABLEH")) {
+ value = constrain(value, 0, 255);
+ logger.console("Setting enable heater signal to output %d", value);
+ config->enableHeaterOutput = value;
+ } else if (command == String("HEATVALV")) {
+ value = constrain(value, 0, 255);
+ logger.console("Setting heater valve signal output %d", value);
+ config->heaterValveOutput = value;
+ } else if (command == String("HEATERON")) {
+ value = constrain(value, 0, 40);
+ logger.console("Setting enable heater temp on to %d deg C", value);
+ config->heaterTemperatureOn = value;
+ } else if (command == String("HEATPUMP")) {
+ value = constrain(value, 0, 255);
+ logger.console("Setting heater pump signal to output %d", value);
+ config->heaterPumpOutput = value;
+ } else if (command == String("COOLPUMP")) {
+ value = constrain(value, 0, 255);
+ logger.console("Setting cooling pump signal to output %d", value);
+ config->coolingPumpOutput = value;
+ } else if (command == String("COOLFAN")) {
+ value = constrain(value, 0, 255);
+ logger.console("Setting cooling fan signal to output %d", value);
+ config->coolingFanOutput = value;
+ } else if (command == String("COOLON")) {
+ value = constrain(value, 0, 200);
+ logger.console("Setting cooling ON temperature to: %d deg C", value);
+ config->coolingTempOn = value;
+ } else if (command == String("COOLOFF")) {
+ value = constrain(value, 0, config->coolingTempOn);
+ logger.console("Setting cooling OFF temperature to: %d deg C", value);
+ config->coolingTempOff = value;
+ } else if (command == String("BRAKELT")) {
+ value = constrain(value, 0, 255);
+ logger.console("Brake light signal set to output %d.", value);
+ config->brakeLightOutput = value;
+ } else if (command == String("REVLT")) {
+ value = constrain(value, 0, 255);
+ logger.console("Reverse light signal set to output %d.", value);
+ config->reverseLightOutput = value;
+ } else if (command == String("PWRSTR")) {
+ value = constrain(value, 0, 255);
+ logger.console("Power steering signal set to output %d.", value);
+ config->powerSteeringOutput = value;
+ } else if (command == String("WARNLT")) {
+ value = constrain(value, 0, 255);
+ logger.console("Warning signal set to output %d.", value);
+ config->warningOutput = value;
+ } else if (command == String("LIMITLT")) {
+ value = constrain(value, 0, 255);
+ logger.console("Limit signal set to output %d.", value);
+ config->powerLimitationOutput = value;
+ } else if (command == String("SOCHG")) {
+ value = constrain(value, 0, 255);
+ logger.console("State of charge set to output %d.", value);
+ config->stateOfChargeOutput = value;
+ } else if (command == String("STLGT")) {
+ value = constrain(value, 0, 255);
+ logger.console("Status light set to output %d.", value);
+ config->statusLightOutput = value;
+ } else if (command == String("STLGTMD")) {
+ logger.console("Status light set to mode %s.", cmdBuffer + command.length() + 1);
+ deviceManager.sendMessage(DEVICE_DISPLAY, STATUSINDICATOR, MSG_UPDATE, (void *)(cmdBuffer + command.length() + 1));
+ } else if (command == String("OUTPUT") && value < 8) {
+ logger.console("DOUT%d, STATE: %d", value, systemIO.getDigitalOut(value));
+ systemIO.setDigitalOut(value, !systemIO.getDigitalOut(value));
+ logger.console("DOUT0:%d, DOUT1:%d, DOUT2:%d, DOUT3:%d, DOUT4:%d, DOUT5:%d, DOUT6:%d, DOUT7:%d", systemIO.getDigitalOut(0),
+ systemIO.getDigitalOut(1), systemIO.getDigitalOut(2), systemIO.getDigitalOut(3), systemIO.getDigitalOut(4), systemIO.getDigitalOut(5),
+ systemIO.getDigitalOut(6), systemIO.getDigitalOut(7));
+ } else {
+ return false;
+ }
+ systemIO.saveConfiguration();
+ return true;
+}
+
+bool SerialConsole::handleConfigCmdCharger(String command, long value)
+{
+ Charger *charger = deviceManager.getCharger();
+ ChargerConfiguration *config = NULL;
+
+ if (!charger) {
+ return false;
+ }
+ config = (ChargerConfiguration *) charger->getConfiguration();
+
+ if (command == String("CHCC")) {
+ value = constrain(value, 0, 100000);
+ logger.console("Setting constant current to %fA", value / 10.0f);
+ config->constantCurrent = value;
+ } else if (command == String("CHCV")) {
+ value = constrain(value, 0, 100000);
+ logger.console("Setting constant voltage to %fV", value / 10.0f);
+ config->constantVoltage = value;
+ } else if (command == String("CHTC")) {
+ value = constrain(value, 0, config->constantCurrent);
+ logger.console("Setting terminate current to %fA", value / 10.0f);
+ config->terminateCurrent = value;
+ } else if (command == String("CHICMX")) {
+ value = constrain(value, 0, 100000);
+ logger.console("Setting max input current to %fV", value / 10.0f);
+ config->maximumInputCurrent = value;
+ } else if (command == String("CHICIN")) {
+ value = constrain(value, 0, 100000);
+ logger.console("Setting initial input current to %fV", value / 10.0f);
+ config->initialInputCurrent = value;
+ } else if (command == String("CHBVMN")) {
+ value = constrain(value, 0, config->maximumBatteryVoltage);
+ logger.console("Setting min battery voltage to %fV", value / 10.0f);
+ config->minimumBatteryVoltage = value;
+ } else if (command == String("CHBVMX")) {
+ value = constrain(value, config->minimumBatteryVoltage, 100000);
+ logger.console("Setting max battery voltage to %fV", value / 10.0f);
+ config->maximumBatteryVoltage = value;
+ } else if (command == String("CHTPMN")) {
+ value = constrain(value, -1000, config->maximumTemperature);
+ logger.console("Setting min battery temp to %f deg C", value / 10.0f);
+ config->minimumTemperature = value;
+ } else if (command == String("CHTPMX")) {
+ value = constrain(value, config->minimumTemperature, 10000);
+ logger.console("Setting max battery temp to %f deg C", value / 10.0f);
+ config->maximumTemperature = value;
+ } else if (command == String("CHAHMX")) {
+ value = constrain(value, 0, 100000);
+ logger.console("Setting max Ampere hours to %fAh", value / 10.0f);
+ config->maximumAmpereHours = value;
+ } else if (command == String("CHCTMX")) {
+ value = constrain(value, 0, 100000);
+ logger.console("Setting max charge time to %d min", value);
+ config->maximumChargeTime = value;
+ } else if (command == String("CHTDRC")) {
+ value = constrain(value, 0, 100000);
+ logger.console("Setting derating of charge current to %fA per deg C", value / 10.0f);
+ config->deratingRate = value;
+ } else if (command == String("CHTDRS")) {
+ value = constrain(value, 0, 10000);
+ logger.console("Setting derating reference temp to %f deg C", value / 10.0f);
+ config->deratingReferenceTemperature = value;
+ } else if (command == String("CHTHYS")) {
+ value = constrain(value, config->hystereseResumeTemperature, 10000);
+ logger.console("Setting hysterese temp to stop charging to %f deg C", value / 10.0f);
+ config->hystereseStopTemperature = value;
+ } else if (command == String("CHTHYR")) {
+ value = constrain(value, 0, config->hystereseStopTemperature);
+ logger.console("Setting hysterese temp to resume charging to %f deg C", value / 10.0f);
+ config->hystereseResumeTemperature = value;
+ } else if (command == String("CHMT")) {
+ value = constrain(value, 0, 10000);
+ logger.console("Setting measure time to %d ms", value);
+ config->measureTime = value;
+ } else if (command == String("CHMC")) {
+ value = constrain(value, 0, 2000);
+ logger.console("Setting measure current to %f A", value / 10.0f);
+ config->measureCurrent = value;
+ } else if (command == String("CHVD")) {
+ value = constrain(value, 1, 100);
+ logger.console("Setting voltage drop divisor to %d", value);
+ config->voltageDrop = value;
+ } else {
+ return false;
+ }
+ charger->saveConfiguration();
+ return true;
+}
+
+bool SerialConsole::handleConfigCmdDcDcConverter(String command, long value)
+{
+ DcDcConverter *dcdcConverter = deviceManager.getDcDcConverter();
+ DcDcConverterConfiguration *config = NULL;
+
+ if (!dcdcConverter) {
+ return false;
+ }
+ config = (DcDcConverterConfiguration *) dcdcConverter->getConfiguration();
+
+ if (command == String("DCMODE")) {
+ logger.console("Setting mode to %s", (value == 0 ? "buck" : "boost"));
+ config->mode = value;
+ } else if (command == String("DCBULV")) {
+ value = constrain(value, 0, 10000);
+ logger.console("Setting buck LV voltage to %fV", value / 10.0f);
+ config->lowVoltageCommand = value;
+ } else if (command == String("DCBULVC")) {
+ value = constrain(value, 0, 10000);
+ logger.console("Setting buck LV current limit to %dA", value);
+ config->lvBuckModeCurrentLimit = value;
+ } else if (command == String("DCBUHVV")) {
+ value = constrain(value, 0, 10000);
+ logger.console("Setting buck HV under voltage limit to %dV", value);
+ config->hvUndervoltageLimit = value;
+ } else if (command == String("DCBUHVC")) {
+ value = constrain(value, 0, 10000);
+ logger.console("Setting buck HV current limit to %fA", value / 10.0f);
+ config->hvBuckModeCurrentLimit = value;
+ } else if (command == String("DCBOHV")) {
+ value = constrain(value, 0, 10000);
+ logger.console("Setting boost HV voltage to %dV", value);
+ config->highVoltageCommand = value;
+ } else if (command == String("DCBOLVV")) {
+ value = constrain(value, 0, 10000);
+ logger.console("Setting boost LV undervoltage limit to %fV", value / 10.0f);
+ config->lvUndervoltageLimit = value;
+ } else if (command == String("DCBOLVC")) {
+ value = constrain(value, 0, 10000);
+ logger.console("Setting boost LV current limit to %dA", value);
+ config->lvBoostModeCurrentLinit = value;
+ } else if (command == String("DCBOHVC")) {
+ value = constrain(value, 0, 10000);
+ logger.console("Setting boost HV current limit to %fA", value / 10.0f);
+ config->hvBoostModeCurrentLimit = value;
+ } else if (command == String("DCDBG") && dcdcConverter->getId() == BRUSA_BSC6) {
+ BrusaBSC6Configuration *bscConfig = (BrusaBSC6Configuration *) config;
+ value = constrain(value, 0, 1);
+ logger.console("Setting BSC6 debug mode %d", value);
+ bscConfig->debugMode = value;
+ } else {
+ return false;
+ }
+ dcdcConverter->saveConfiguration();
+ return true;
}
-void SerialConsole::handleShortCmd() {
- uint8_t val;
- MotorController* motorController = (MotorController*) DeviceManager::getInstance()->getMotorController();
- Throttle *accelerator = DeviceManager::getInstance()->getAccelerator();
- Throttle *brake = DeviceManager::getInstance()->getBrake();
- DeviceManager *deviceManager = DeviceManager::getInstance();
-
- switch (cmdBuffer[0]) {
- case 'h':
- case '?':
- case 'H':
- printMenu();
- break;
- case 'L':
- if (heartbeat != NULL) {
- heartbeat->setThrottleDebug(!heartbeat->getThrottleDebug());
- if (heartbeat->getThrottleDebug()) {
- Logger::console("Output raw throttle");
- } else {
- Logger::console("Cease raw throttle output");
- }
- }
- break;
- case 'U':
- Logger::console("Adding a sequence of values from 0 to 255 into eeprom");
- for (int i = 0; i < 256; i++) {
- memCache->Write(1000 + i, (uint8_t) i);
- }
- Logger::info("Flushing cache");
- memCache->FlushAllPages(); //write everything to eeprom
- memCache->InvalidateAll(); //remove all data from cache
- Logger::console("Operation complete.");
- break;
- case 'I':
- Logger::console("Retrieving data previously saved");
- for (int i = 0; i < 256; i++) {
- memCache->Read(1000 + i, &val);
- Logger::console("%d: %d", i, val);
- }
- break;
- case 'E':
- Logger::console("Reading System EEPROM values");
- for (int i = 0; i < 256; i++) {
- memCache->Read(EE_SYSTEM_START + i, &val);
- Logger::console("%d: %d", i, val);
- }
- break;
- case 'K': //set all outputs high
- for (int tout = 0; tout < NUM_OUTPUT; tout++) setOutput(tout, true);
- Logger::console("all outputs: ON");
- break;
- case 'J': //set the four outputs low
- for (int tout = 0; tout < NUM_OUTPUT; tout++) setOutput(tout, false);
- Logger::console("all outputs: OFF");
- break;
- case 'z': // detect throttle min/max & other details
- if (accelerator) {
- ThrottleDetector *detector = new ThrottleDetector(accelerator);
- detector->detect();
- }
- break;
- case 'Z': // save throttle settings
- if (accelerator) {
- accelerator->saveConfiguration();
- }
- break;
- case 'b':
- if (brake) {
- ThrottleDetector *detector = new ThrottleDetector(brake);
- detector->detect();
- }
- break;
- case 'B':
- if (brake != NULL) {
- brake->saveConfiguration();
- }
- break;
- case 'p':
- Logger::console("PASSTHROUGH MODE - All traffic Serial3 <-> SerialUSB");
- //this never stops so basically everything dies. you will have to reboot.
- int inSerialUSB, inSerial3;
- while (1 == 1) {
- inSerialUSB = SerialUSB.read();
- inSerial3 = Serial3.read();
- if (inSerialUSB > -1) {
- Serial3.write((char) inSerialUSB);
- }
- if (inSerial3 > -1) {
- SerialUSB.write((char) inSerial3);
- }
- }
- break;
-
- case 'S':
- //there is not really any good way (currently) to auto generate this list
- //the information just isn't stored anywhere in code. Perhaps we might
- //think to change that. Otherwise you must remember to update here or
- //nobody will know your device exists. Additionally, these values are
- //decoded into decimal from their hex specification in DeviceTypes.h
- Logger::console("DMOC645 = %X", DMOC645);
- Logger::console("Brusa DMC5 = %X", BRUSA_DMC5);
- Logger::console("Brusa Charger = %X", BRUSACHARGE);
- Logger::console("TCCH Charger = %X", TCCHCHARGE);
- Logger::console("Pot based accelerator = %X", POTACCELPEDAL);
- Logger::console("Pot based brake = %X", POTBRAKEPEDAL);
- Logger::console("CANBus accelerator = %X", CANACCELPEDAL);
- Logger::console("CANBus brake = %X", CANBRAKEPEDAL);
- Logger::console("WIFI (iChip2128) = %X", ICHIP2128);
- Logger::console("Th!nk City BMS = %X", THINKBMS);
- break;
- case 's':
- Logger::console("Finding and listing all nearby WiFi access points");
- deviceManager->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)"RP20");
- break;
- case 'W':
- Logger::console("Setting Wifi Adapter to WPS mode (make sure you press the WPS button on your router)");
- // restore factory defaults and give it some time
- deviceManager->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)"AWPS");
- break;
- case 'w':
- Logger::console("Resetting wifi to factory defaults and setting up GEVCU4.2 Ad Hoc network");
- // restore factory defaults and give it some time
- // pinMode(43,OUTPUT);
- // digitalWrite(43, LOW); //Pin 43 held low for 5 seconds puts Version 4.2 in Recovery mode
- // delay(6000);
- // digitalWrite(43, HIGH);
- // delay(3000);
- deviceManager->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)"FD");//Reset
- delay(2000);
- deviceManager->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)"HIF=1"); //Set for RS-232 serial.
- delay(1000);
- deviceManager->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)"BDRA");//Auto baud rate selection
- delay(1000);
- deviceManager->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)"WLCH=9"); //use whichever channel an AP wants to use
- delay(1000);
- deviceManager->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)"WLSI=!GEVCU"); //set for GEVCU aS AP.
- delay(1000);
- deviceManager->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)"DIP=192.168.3.10"); //enable IP
- delay(1000);
- deviceManager->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)"DPSZ=8"); //set DHCP server for 8
- delay(1000);
- deviceManager->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)"RPG=secret"); // set the configuration password for /ichip
- delay(1000);
- deviceManager->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)"WPWD=secret"); // set the password to update config params
- delay(1000);
- deviceManager->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)"AWS=1"); //turn on web server
- delay(1000);
- deviceManager->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)"DOWN"); //cause a reset to allow it to come up with the settings
- delay(5000); // a 5 second delay is required for the chip to come back up ! Otherwise commands will be lost
-
- deviceManager->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_CONFIG_CHANGE, NULL); // reload configuration params as they were lost
- Logger::console("Wifi 4.2 initialized");
- break;
-
- case 'X':
- setup(); //this is probably a bad idea. Do not do this while connected to anything you care about - only for debugging in safety!
- break;
- }
+bool SerialConsole::handleConfigCmdSystem(String command, long value, char *parameter)
+{
+
+ if (command == String("ENABLE")) {
+ if (!deviceManager.sendMessage(DEVICE_ANY, (DeviceId) value, MSG_ENABLE, NULL)) {
+ logger.console("Invalid device ID (%#x, %d)", value, value);
+ }
+ } else if (command == String("DISABLE")) {
+ if (!deviceManager.sendMessage(DEVICE_ANY, (DeviceId) value, MSG_DISABLE, NULL)) {
+ logger.console("Invalid device ID (%#x, %d)", value, value);
+ }
+ } else if (command == String("KILL")) {
+ if (!deviceManager.sendMessage(DEVICE_ANY, (DeviceId) value, MSG_KILL, NULL)) {
+ logger.console("Invalid device ID (%#x, %d)", value, value);
+ }
+ } else if (command == String("SYSTYPE")) {
+ systemIO.setSystemType((SystemIOConfiguration::SystemType) constrain(value, SystemIOConfiguration::GEVCU1, SystemIOConfiguration::GEVCU4));
+ logger.console("System type updated. Power cycle to apply.");
+ } else if (command == String("LOGLEVEL")) {
+ if (strchr(parameter, ',') == NULL) {
+ logger.setLoglevel((Logger::LogLevel) value);
+ logger.console("setting loglevel to %d", value);
+ systemIO.setLogLevel(logger.getLogLevel());
+ } else {
+ DeviceId deviceId = (DeviceId) strtol(strtok(parameter, ","), NULL, 0);
+ Device *device = deviceManager.getDeviceByID(deviceId);
+ if (device != NULL) {
+ value = atol(strtok(NULL, ","));
+ logger.setLoglevel(device, (Logger::LogLevel) value);
+ }
+ }
+ } else if (command == String("NUKE") && value == 1) {
+ // write zero to the checksum location of every device in the table.
+ uint8_t zeroVal = 0;
+ for (int j = 0; j < 64; j++) {
+ memCache.Write(EE_DEVICES_BASE + (EE_DEVICE_SIZE * j), zeroVal);
+ memCache.FlushAllPages();
+ }
+ logger.console("Device settings have been nuked. Reboot to reload default settings");
+ } else {
+ return false;
+ }
+ return true;
+}
+
+bool SerialConsole::handleConfigCmdWifi(String command, String parameter)
+{
+ if (command == String("WLAN")) {
+ deviceManager.sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *) parameter.c_str());
+ logger.info("sent \"AT+i%s\" to wifi device", parameter.c_str());
+ } else if (command == String("SSID")) {
+ sendWifiCommand("WLSI=", parameter);
+ } else if (command == String("IP")) {
+ sendWifiCommand("DIP=", parameter);
+ } else if (command == String("CHANNEL")) {
+ sendWifiCommand("WLCH=", parameter);
+ } else if (command == String("SECURITY")) {
+ sendWifiCommand("WLPP=", parameter);
+ } else if (command == String("PWD")) {
+ sendWifiCommand("WPWD=", parameter);
+ } else {
+ return false;
+ }
+ return true;
+}
+
+void SerialConsole::sendWifiCommand(String command, String parameter)
+{
+ command.concat("=");
+ command.concat(parameter);
+ logger.info("sent \"AT+i%s\" to wifi device", command.c_str());
+ deviceManager.sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *) command.c_str());
+}
+
+bool SerialConsole::handleConfigCmdCanOBD2(String command, long value)
+{
+ CanOBD2 *canObd2 = (CanOBD2 *) deviceManager.getDeviceByID(CANOBD2);
+ CanOBD2Configuration *config = NULL;
+
+ if (!canObd2) {
+ return false;
+ }
+ config = (CanOBD2Configuration *) canObd2->getConfiguration();
+
+ if (command == String("ODBRES")) {
+ value = constrain(value, 0, 1);
+ logger.console("Setting listener can bus to %d", value);
+ config->canBusRespond = value;
+ } else if (command == String("ODBRESO")) {
+ value = constrain(value, 0, 7);
+ logger.console("Setting respond can ID offset to %d", value);
+ config->canIdOffsetRespond = value;
+ } else if (command == String("OBDPOL")) {
+ value = constrain(value, 0, 1);
+ logger.console("Setting query can bus to %d", value);
+ config->canBusPoll = value;
+ } else if (command == String("OBDPOLO")) {
+ if (value != 255) {
+ value = constrain(value, 0, 7);
+ }
+ logger.console("Setting request can ID to %d", value);
+ config->canIdOffsetPoll = value;
+ } else {
+ return false;
+ }
+ canObd2->saveConfiguration();
+ return true;
+}
+
+void SerialConsole::handleShortCmd()
+{
+ uint8_t val;
+ Throttle *accelerator = deviceManager.getAccelerator();
+ Throttle *brake = deviceManager.getBrake();
+ Heartbeat *heartbeat = (Heartbeat *) deviceManager.getDeviceByID(HEARTBEAT);
+
+ switch (cmdBuffer[0]) {
+ case 'h':
+ case '?':
+ case 'H':
+ printMenu();
+ break;
+
+ case 'L':
+ if (heartbeat != NULL) {
+ heartbeat->setThrottleDebug(!heartbeat->getThrottleDebug());
+
+ if (heartbeat->getThrottleDebug()) {
+ logger.console("Output raw throttle");
+ } else {
+ logger.console("Cease raw throttle output");
+ }
+ }
+ break;
+
+ case 'U':
+ logger.console("Adding a sequence of values from 0 to 255 into eeprom");
+
+ for (int i = 0; i < 256; i++) {
+ memCache.Write(1000 + i, (uint8_t) i);
+ }
+
+ logger.info("Flushing cache");
+ memCache.FlushAllPages(); //write everything to eeprom
+ memCache.InvalidateAll(); //remove all data from cache
+ logger.console("Operation complete.");
+ break;
+
+ case 'I':
+ logger.console("Retrieving data previously saved");
+
+ for (int i = 0; i < 256; i++) {
+ memCache.Read(1000 + i, &val);
+ logger.console("%d: %d", i, val);
+ }
+ break;
+
+ case 'K': //set all outputs high
+ for (int tout = 0; tout < CFG_NUMBER_DIGITAL_OUTPUTS; tout++) {
+ systemIO.setDigitalOut(tout, true);
+ }
+
+ logger.console("all outputs: ON");
+ break;
+
+ case 'J': //set the four outputs low
+ for (int tout = 0; tout < CFG_NUMBER_DIGITAL_OUTPUTS; tout++) {
+ systemIO.setDigitalOut(tout, false);
+ }
+
+ logger.console("all outputs: OFF");
+ break;
+
+ case 'z': // detect throttle min/max & other details
+ if (accelerator) {
+ ThrottleDetector *detector = new ThrottleDetector(accelerator);
+ detector->detect();
+ }
+ break;
+
+ case 'Z': // save throttle settings
+ if (accelerator) {
+ accelerator->saveConfiguration();
+ }
+ break;
+
+ case 'b':
+ if (brake) {
+ ThrottleDetector *detector = new ThrottleDetector(brake);
+ detector->detect();
+ }
+ break;
+
+ case 'B':
+ if (brake != NULL) {
+ brake->saveConfiguration();
+ }
+ break;
+
+ case 'p':
+ logger.console("PASSTHROUGH MODE - All traffic Serial3 <-> SerialUSB");
+ //this never stops so basically everything dies. you will have to reboot.
+ int inSerialUSB, inSerial3;
+
+ while (1 == 1) {
+ inSerialUSB = SerialUSB.read();
+ inSerial3 = Serial3.read();
+
+ if (inSerialUSB > -1) {
+ Serial3.write((char) inSerialUSB);
+ }
+
+ if (inSerial3 > -1) {
+ SerialUSB.write((char) inSerial3);
+ }
+ }
+ break;
+
+ case 'S':
+ deviceManager.printDeviceList();
+ break;
+
+ case 's':
+ logger.console("Finding and listing all nearby WiFi access points");
+ deviceManager.sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *) "RP20");
+ break;
+
+ case 'W':
+ logger.console("Setting Wifi Adapter to WPS mode (make sure you press the WPS button on your router)");
+ // restore factory defaults and give it some time
+ deviceManager.sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *) "AWPS");
+ break;
+
+ case 'w':
+ logger.console("Resetting wifi to factory defaults and setting up AP, this takes about 50sec, please stand-by");
+ deviceManager.sendMessage(DEVICE_WIFI, ICHIP2128, MSG_RESET, NULL);
+ deviceManager.sendMessage(DEVICE_WIFI, ICHIP2128, MSG_CONFIG_CHANGE, NULL); // reload configuration params as they were lost
+ logger.console("Wifi initialized");
+ break;
+
+ case 'X':
+ setup(); //this is probably a bad idea. Do not do this while connected to anything you care about - only for debugging in safety!
+ break;
+
+ case 'P':
+ logger.console("measuring pre-charge cycle");
+ systemIO.measurePreCharge();
+ break;
+ }
}
diff --git a/SerialConsole.h b/SerialConsole.h
index d6169ff..e11b1a9 100644
--- a/SerialConsole.h
+++ b/SerialConsole.h
@@ -31,43 +31,61 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
#include "Heartbeat.h"
#include "MemCache.h"
#include "config.h"
-#include "sys_io.h"
+#include "SystemIO.h"
#include "PotThrottle.h"
+#include "PotBrake.h"
+#include "CanThrottle.h"
+#include "CanBrake.h"
#include "DeviceManager.h"
#include "MotorController.h"
-#include "DmocMotorController.h" //TODO: direct reference to dmoc must be removed
+#include "BrusaDMC5.h"
+#include "BrusaBSC6.h"
#include "ThrottleDetector.h"
-#include "ichip_2128.h"
+#include "CanOBD2.h"
+#include "WifiIchip2128.h"
-class SerialConsole {
+class SerialConsole
+{
public:
- SerialConsole(MemCache* memCache);
- SerialConsole(MemCache* memCache, Heartbeat* heartbeat);
- void loop();
- void printMenu();
+ SerialConsole();
+ void loop();
+ void printMenu();
protected:
- enum CONSOLE_STATE
- {
- STATE_ROOT_MENU
- };
+ enum CONSOLE_STATE
+ {
+ STATE_ROOT_MENU
+ };
private:
- Heartbeat* heartbeat;
- MemCache* memCache;
bool handlingEvent;
- char cmdBuffer[80];
- int ptrBuffer;
- int state;
- int loopcount;
- bool cancel;
-
-
- void init();
+ char cmdBuffer[80];
+ int ptrBuffer;
+ int state;
+
void serialEvent();
- void handleConsoleCmd();
- void handleShortCmd();
- void handleConfigCmd();
+ void sendWifiCommand(String command, String parameter);
+ void handleConsoleCmd();
+ void handleShortCmd();
+ void handleCmd();
+ bool handleConfigCmdMotorController(String command, long value);
+ bool handleConfigCmdThrottle(String command, long value);
+ bool handleConfigCmdBrake(String command, long value);
+ bool handleConfigCmdSystemIO(String command, long value);
+ bool handleConfigCmdCharger(String command, long value);
+ bool handleConfigCmdDcDcConverter(String command, long value);
+ bool handleConfigCmdSystem(String command, long value, char *parameter);
+ bool handleConfigCmdWifi(String command, String parameter);
+ bool handleConfigCmdCanOBD2(String command, long value);
+ void printMenuMotorController();
+ void printMenuThrottle();
+ void printMenuBrake();
+ void printMenuSystemIO();
+ void printMenuCharger();
+ void printMenuDcDcConverter();
+ void printMenuCanOBD2();
};
+extern SerialConsole serialConsole;
+
#endif /* SERIALCONSOLE_H_ */
diff --git a/Sha1.cpp b/Sha1.cpp
new file mode 100644
index 0000000..a6fc61e
--- /dev/null
+++ b/Sha1.cpp
@@ -0,0 +1,159 @@
+#include
+#include "Sha1.h"
+
+#define SHA1_K0 0x5a827999
+#define SHA1_K20 0x6ed9eba1
+#define SHA1_K40 0x8f1bbcdc
+#define SHA1_K60 0xca62c1d6
+
+const uint8_t sha1InitState[] PROGMEM = {
+ 0x01,0x23,0x45,0x67, // H0
+ 0x89,0xab,0xcd,0xef, // H1
+ 0xfe,0xdc,0xba,0x98, // H2
+ 0x76,0x54,0x32,0x10, // H3
+ 0xf0,0xe1,0xd2,0xc3 // H4
+};
+
+void Sha1Class::init(void) {
+ memcpy_P(state.b,sha1InitState,HASH_LENGTH);
+ byteCount = 0;
+ bufferOffset = 0;
+}
+
+uint32_t Sha1Class::rol32(uint32_t number, uint8_t bits) {
+ return ((number << bits) | (number >> (32-bits)));
+}
+
+void Sha1Class::hashBlock() {
+ uint8_t i;
+ uint32_t a,b,c,d,e,t;
+
+ a=state.w[0];
+ b=state.w[1];
+ c=state.w[2];
+ d=state.w[3];
+ e=state.w[4];
+ for (i=0; i<80; i++) {
+ if (i>=16) {
+ t = buffer.w[(i+13)&15] ^ buffer.w[(i+8)&15] ^ buffer.w[(i+2)&15] ^ buffer.w[i&15];
+ buffer.w[i&15] = rol32(t,1);
+ }
+ if (i<20) {
+ t = (d ^ (b & (c ^ d))) + SHA1_K0;
+ } else if (i<40) {
+ t = (b ^ c ^ d) + SHA1_K20;
+ } else if (i<60) {
+ t = ((b & c) | (d & (b | c))) + SHA1_K40;
+ } else {
+ t = (b ^ c ^ d) + SHA1_K60;
+ }
+ t+=rol32(a,5) + e + buffer.w[i&15];
+ e=d;
+ d=c;
+ c=rol32(b,30);
+ b=a;
+ a=t;
+ }
+ state.w[0] += a;
+ state.w[1] += b;
+ state.w[2] += c;
+ state.w[3] += d;
+ state.w[4] += e;
+}
+
+void Sha1Class::addUncounted(uint8_t data) {
+ buffer.b[bufferOffset ^ 3] = data;
+ bufferOffset++;
+ if (bufferOffset == BLOCK_LENGTH) {
+ hashBlock();
+ bufferOffset = 0;
+ }
+}
+
+#if defined(ARDUINO) && ARDUINO >= 100
+size_t
+#else
+void
+#endif
+Sha1Class::write(uint8_t data) {
+ ++byteCount;
+ addUncounted(data);
+#if defined(ARDUINO) && ARDUINO >= 100
+ return 1;
+#endif
+}
+
+void Sha1Class::pad() {
+ // Implement SHA-1 padding (fips180-2 §5.1.1)
+
+ // Pad with 0x80 followed by 0x00 until the end of the block
+ addUncounted(0x80);
+ while (bufferOffset != 56) addUncounted(0x00);
+
+ // Append length in the last 8 bytes
+ addUncounted(0); // We're only using 32 bit lengths
+ addUncounted(0); // But SHA-1 supports 64 bit lengths
+ addUncounted(0); // So zero pad the top bits
+ addUncounted(byteCount >> 29); // Shifting to multiply by 8
+ addUncounted(byteCount >> 21); // as SHA-1 supports bitstreams as well as
+ addUncounted(byteCount >> 13); // byte.
+ addUncounted(byteCount >> 5);
+ addUncounted(byteCount << 3);
+}
+
+
+uint8_t* Sha1Class::result(void) {
+ // Pad to complete the last block
+ pad();
+
+ // Swap byte order back
+ for (int i=0; i<5; i++) {
+ uint32_t a,b;
+ a=state.w[i];
+ b=a<<24;
+ b|=(a<<8) & 0x00ff0000;
+ b|=(a>>8) & 0x0000ff00;
+ b|=a>>24;
+ state.w[i]=b;
+ }
+
+ // Return pointer to hash (20 characters)
+ return state.b;
+}
+
+/*
+#define HMAC_IPAD 0x36
+#define HMAC_OPAD 0x5c
+
+void Sha1Class::initHmac(const uint8_t* key, int keyLength) {
+ uint8_t i;
+ memset(keyBuffer,0,BLOCK_LENGTH);
+ if (keyLength > BLOCK_LENGTH) {
+ // Hash long keys
+ init();
+ for (;keyLength--;) write(*key++);
+ memcpy(keyBuffer,result(),HASH_LENGTH);
+ } else {
+ // Block length keys are used as is
+ memcpy(keyBuffer,key,keyLength);
+ }
+ // Start inner hash
+ init();
+ for (i=0; i
+#include "Print.h"
+
+#define HASH_LENGTH 20
+#define BLOCK_LENGTH 64
+
+union _buffer {
+ uint8_t b[BLOCK_LENGTH];
+ uint32_t w[BLOCK_LENGTH/4];
+};
+union _state {
+ uint8_t b[HASH_LENGTH];
+ uint32_t w[HASH_LENGTH/4];
+};
+
+class Sha1Class : public Print // @suppress("Class has a virtual method and non-virtual destructor")
+{
+ public:
+ void init(void);
+ void initHmac(const uint8_t* secret, int secretLength);
+ uint8_t* result(void);
+ uint8_t* resultHmac(void);
+#if defined(ARDUINO) && ARDUINO >= 100
+ virtual size_t write(uint8_t);
+#else
+ virtual void write(uint8_t);
+#endif
+ using Print::write;
+ private:
+ void pad();
+ void addUncounted(uint8_t data);
+ void hashBlock();
+ uint32_t rol32(uint32_t number, uint8_t bits);
+ _buffer buffer;
+ uint8_t bufferOffset;
+ _state state;
+ uint32_t byteCount;
+ uint8_t keyBuffer[BLOCK_LENGTH];
+ uint8_t innerHash[HASH_LENGTH];
+
+};
+extern Sha1Class Sha1;
+
+#endif
diff --git a/SocketProcessor.h b/SocketProcessor.h
new file mode 100644
index 0000000..53b2b36
--- /dev/null
+++ b/SocketProcessor.h
@@ -0,0 +1,46 @@
+/*
+ * SocketProcessor.h
+ *
+ * Abstract Class / interface to handle socket data
+ *
+ Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
+
+ 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 SOCKETPROCESSOR_H_
+#define SOCKETPROCESSOR_H_
+
+#include
+/*
+ * Interface
+ */
+class SocketProcessor
+{
+public:
+ virtual ~SocketProcessor() {}
+ virtual String generateUpdate() = 0; // generate socket specific update message which gets sent on a regular basis
+ virtual String generateLogEntry(String logLevel, String deviceName, String message) = 0; // convert a log message to a socket specific message
+ virtual String processInput(char *input) = 0; // process input from a socket and return data (NULL means disconnect socket)
+private:
+
+};
+
+#endif /* SOCKETPROCESSOR_H_ */
diff --git a/Status.cpp b/Status.cpp
new file mode 100644
index 0000000..7b8b99a
--- /dev/null
+++ b/Status.cpp
@@ -0,0 +1,432 @@
+/*
+ * Status.cpp
+ *
+ Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
+
+ 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 "Status.h"
+#include "DeviceManager.h"
+
+Status status;
+
+/*
+ * Constructor
+ */
+Status::Status()
+{
+ systemState = startup;
+
+ limitationTorque = false;
+ limitationMaxTorque = false;
+ limitationSpeed = false;
+ limitationControllerTemperature = false;
+ limitationMotorTemperature = false;
+ limitationSlewRate = false;
+ limitationMotorModel = false;
+ limitationMechanicalPower = false;
+ limitationAcVoltage = false;
+ limitationAcCurrent = false;
+ limitationDcVoltage = false;
+ limitationDcCurrent = false;
+
+ warning = false;
+ oscillationLimiter= false;
+ maximumModulationLimiter = false;
+ systemCheckActive = false;
+
+ overtempController = false;
+ overtempMotor = false;
+ overspeed = false;
+ hvUndervoltage = false;
+ hvOvervoltage = false;
+ hvOvercurrent = false;
+ acOvercurrent = false;
+
+ preChargeRelay = false;
+ mainContactor = false;
+ secondaryContactor = false;
+ fastChargeContactor = false;
+
+ enableMotor = false;
+ enableCharger = false;
+ enableDcDc = false;
+ enableHeater = false;
+ enableRegen = true;
+ enableCreep = true;
+
+ heaterValve = false;
+ heaterPump = false;
+ coolingPump = false;
+ coolingFan = false;
+
+ brakeLight = false;
+ reverseLight = false;
+ powerSteering = false;
+ unused = false;
+
+ enableIn = false;
+ chargePowerAvailable= false;
+ interlockPresent = false;
+ reverseInput = false;
+ absActive = false;
+ gearChangeActive = false;
+ statusLight = false;
+ brakeHold = false;
+
+ flowCoolant = 0;
+ flowHeater = 0;
+ heaterPower = 0;
+
+ bmsDclLowSoc = false;
+ bmsDclHighCellResistance = false;
+ bmsDclTemperature = false;
+ bmsDclLowCellVoltage = false;
+ bmsDclLowPackVoltage = false;
+ bmsDclCclVoltageFailsafe = false;
+ bmsDclCclCommunication = false;
+ bmsCclHighSoc = false;
+ bmsCclHighCellResistance = false;
+ bmsCclTemperature = false;
+ bmsCclHighCellVoltage = false;
+ bmsCclHighPackVoltage = false;
+ bmsCclChargerLatch = false;
+ bmsCclAlternate = false;
+ bmsRelayDischarge = false;
+ bmsRelayCharge = false;
+ bmsChagerSafety = false;
+ bmsDtcPresent = false;
+ bmsVoltageFailsafe = false;
+ bmsCurrentFailsafe = false;
+ bmsDepleted = false;
+ bmsBalancingActive = false;
+ bmsDtcWeakCellFault = false;
+ bmsDtcLowCellVolage = false;
+ bmsDtcHVIsolationFault = false;
+ bmsDtcVoltageRedundancyFault = false;
+
+ for (int i = 0; i < CFG_NUMBER_DIGITAL_OUTPUTS; i++) {
+ digitalOutput[i] = false;
+ }
+ for (int i = 0; i < CFG_NUMBER_DIGITAL_INPUTS; i++) {
+ digitalInput[i] = false;
+ }
+ for (int i = 0; i < CFG_NUMBER_BATTERY_TEMPERATURE_SENSORS; i++) {
+ temperatureBattery[i] = CFG_NO_TEMPERATURE_DATA;
+ }
+ temperatureCoolant = CFG_NO_TEMPERATURE_DATA;
+ heaterTemperature = CFG_NO_TEMPERATURE_DATA;
+ temperatureExterior = CFG_NO_TEMPERATURE_DATA;
+ barometricPressure = 0;
+ vehicleSpeed = 0;
+
+ stateOfCharge = 0;
+ dcdcRunning = false;
+ stateTimestamp = 0;
+}
+
+/*
+ * Retrieve the current system state.
+ */
+Status::SystemState Status::getSystemState()
+{
+ return systemState;
+}
+
+/*
+ * Set a new system state. The new system state is validated if the
+ * transition is allowed from the old state. If an invalid transition is
+ * attempted, the new state will be 'error'.
+ * The old and new state are broadcast to all devices.
+ */
+Status::SystemState Status::setSystemState(SystemState newSystemState)
+{
+ if (systemState == newSystemState) {
+ return systemState;
+ }
+
+ SystemState oldSystemState = systemState;
+
+ if (newSystemState == error) {
+ systemState = error;
+ } else {
+ switch (systemState) {
+ case startup:
+ if (newSystemState == init) {
+ systemState = newSystemState;
+ }
+ break;
+ case init:
+ if (newSystemState == preCharge) {
+ systemState = newSystemState;
+ }
+ break;
+ case preCharge:
+ if (newSystemState == preCharged) {
+ systemState = newSystemState;
+ }
+ break;
+ case preCharged:
+ if (newSystemState == ready) {
+ systemState = newSystemState;
+ }
+ break;
+ case batteryHeating:
+ if (newSystemState == charging || newSystemState == ready) {
+ systemState = newSystemState;
+ }
+ break;
+ case charging:
+ if (newSystemState == charged || newSystemState == ready) {
+ systemState = newSystemState;
+ }
+ break;
+ case charged:
+ if (newSystemState == ready || newSystemState == shutdown) {
+ systemState = newSystemState;
+ }
+ break;
+ case ready:
+ if (newSystemState == running || newSystemState == charging || newSystemState == batteryHeating) {
+ systemState = newSystemState;
+ }
+ break;
+ case running:
+ if (newSystemState == ready) {
+ systemState = newSystemState;
+ }
+ break;
+ case shutdown:
+ case error:
+ break;
+ }
+ }
+ if (systemState == newSystemState) {
+ logger.debug("switching to system state '%s'", systemStateToStr(systemState).c_str());
+ stateTimestamp = millis();
+ } else {
+ logger.error("switching from system state '%s' to '%s' is not allowed", systemStateToStr(systemState).c_str(), systemStateToStr(newSystemState).c_str());
+ systemState = error;
+ }
+
+ SystemState params[] = { oldSystemState, systemState };
+ deviceManager.sendMessage(DEVICE_ANY, INVALID, MSG_STATE_CHANGE, params);
+
+ return systemState;
+}
+
+int16_t Status::getLowestBatteryTemperature() {
+ int16_t temp = CFG_NO_TEMPERATURE_DATA;
+
+ for (int i = 0; i < CFG_NUMBER_BATTERY_TEMPERATURE_SENSORS; i++) {
+ temp = min(temp, temperatureBattery[i]);
+ }
+ return temp;
+}
+
+int16_t Status::getHighestBatteryTemperature() {
+ int16_t temp = -9999;
+
+ for (int i = 0; i < CFG_NUMBER_BATTERY_TEMPERATURE_SENSORS; i++) {
+ if (temperatureBattery[i] != CFG_NO_TEMPERATURE_DATA) {
+ temp = max(temp, temperatureBattery[i]);
+ }
+ }
+ return (temp == -9999 ? CFG_NO_TEMPERATURE_DATA : temp);
+}
+
+/*
+ * Convert the current state into a string.
+ */
+String Status::systemStateToStr(SystemState state)
+{
+ switch (state) {
+ case startup:
+ return "unknown";
+ case init:
+ return "init";
+ case preCharge:
+ return "pre-charge";
+ case preCharged:
+ return "pre-charged";
+ case ready:
+ return "ready";
+ case running:
+ return "running";
+ case error:
+ return "error";
+ case batteryHeating:
+ return "battery heating";
+ case charging:
+ return "charging";
+ case charged:
+ return "charged";
+ case shutdown:
+ return "shut-down";
+ }
+ logger.error("the system state is invalid, contact your support!");
+ return "invalid";
+}
+
+/*
+ * Calculate the bit field 1 from the respective flags for faster transmission
+ * to the web site.
+ *
+ * Bitfield contains warnings, errors and torque limitation information from the motor controller
+ */
+uint32_t Status::getBitFieldMotor() {
+ uint32_t bitfield = 0;
+
+ // warnings
+ bitfield |= (warning ? 1 << 0 : 0); // 0x00000001
+ bitfield |= (oscillationLimiter ? 1 << 1 : 0); // 0x00000002
+ bitfield |= (maximumModulationLimiter ? 1 << 2 : 0); // 0x00000004
+// bitfield |= (reserve ? 1 << 3 : 0); // 0x00000008
+// bitfield |= (reserve ? 1 << 4 : 0); // 0x00000010
+// bitfield |= (reserve ? 1 << 5 : 0); // 0x00000020
+// bitfield |= (reserve ? 1 << 6 : 0); // 0x00000040
+// bitfield |= (reserve ? 1 << 7 : 0); // 0x00000080
+
+ // errors
+ bitfield |= (overtempController ? 1 << 8 : 0); // 0x00000100
+ bitfield |= (overtempMotor ? 1 << 9 : 0); // 0x00000200
+ bitfield |= (overspeed ? 1 << 10 : 0); // 0x00000400
+ bitfield |= (hvUndervoltage ? 1 << 11 : 0); // 0x00000800
+ bitfield |= (hvOvervoltage ? 1 << 12 : 0); // 0x00001000
+ bitfield |= (hvOvercurrent ? 1 << 13 : 0); // 0x00002000
+ bitfield |= (acOvercurrent ? 1 << 14 : 0); // 0x00004000
+// bitfield |= (reserve ? 1 << 15 : 0); // 0x00008000
+
+ // limitations
+ bitfield |= (limitationTorque ? 1 << 16 : 0); // 0x00010000
+ bitfield |= (limitationMaxTorque ? 1 << 17 : 0); // 0x00020000
+ bitfield |= (limitationSpeed ? 1 << 18 : 0); // 0x00040000
+ bitfield |= (limitationControllerTemperature ? 1 << 19 : 0); // 0x00080000
+ bitfield |= (limitationMotorTemperature ? 1 << 20 : 0); // 0x00100000
+ bitfield |= (limitationSlewRate ? 1 << 21 : 0); // 0x00200000
+ bitfield |= (limitationMotorModel ? 1 << 22 : 0); // 0x00400000
+ bitfield |= (limitationMechanicalPower ? 1 << 23 : 0); // 0x00800000
+ bitfield |= (limitationAcVoltage ? 1 << 24 : 0); // 0x01000000
+ bitfield |= (limitationAcCurrent ? 1 << 25 : 0); // 0x02000000
+ bitfield |= (limitationDcVoltage ? 1 << 26 : 0); // 0x04000000
+ bitfield |= (limitationDcCurrent ? 1 << 27 : 0); // 0x08000000
+// bitfield |= (reserve ? 1 << 28 : 0); // 0x10000000
+// bitfield |= (reserve ? 1 << 29 : 0); // 0x20000000
+// bitfield |= (reserve ? 1 << 30 : 0); // 0x40000000
+// bitfield |= (reserve ? 1 << 31 : 0); // 0x80000000
+
+ return bitfield;
+}
+
+/*
+ * Calculate the bit field 2 from the respective flags for faster transmission
+ * to the web site.
+ *
+ * Bitfield contains bms information
+ */
+uint32_t Status::getBitFieldBms() {
+ uint32_t bitfield = 0;
+
+ // status
+ bitfield |= (bmsRelayDischarge ? 1 << 0 : 0); // 0x00000001
+ bitfield |= (bmsRelayCharge ? 1 << 1 : 0); // 0x00000002
+ bitfield |= (bmsChagerSafety ? 1 << 2 : 0); // 0x00000004
+ bitfield |= (bmsDtcPresent ? 1 << 3 : 0); // 0x00000008
+// bitfield |= (reserve ? 1 << 4 : 0); // 0x00000010
+// bitfield |= (reserve ? 1 << 5 : 0); // 0x00000020
+// bitfield |= (reserve ? 1 << 6 : 0); // 0x00000040
+// bitfield |= (reserve ? 1 << 7 : 0); // 0x00000080
+
+ bitfield |= (bmsVoltageFailsafe ? 1 << 8 : 0); // 0x00000100
+ bitfield |= (bmsCurrentFailsafe ? 1 << 9 : 0); // 0x00000200
+ bitfield |= (bmsDepleted ? 1 << 10 : 0); // 0x00000400
+ bitfield |= (bmsBalancingActive ? 1 << 11 : 0); // 0x00000800
+ bitfield |= (bmsDtcWeakCellFault ? 1 << 12 : 0); // 0x00001000
+ bitfield |= (bmsDtcLowCellVolage ? 1 << 13 : 0); // 0x00002000
+ bitfield |= (bmsDtcHVIsolationFault ? 1 << 14 : 0); // 0x00004000
+ bitfield |= (bmsDtcVoltageRedundancyFault ? 1 << 15 : 0); // 0x00008000
+
+ // limitations
+ bitfield |= (bmsDclLowSoc ? 1 << 16 : 0); // 0x00010000
+ bitfield |= (bmsDclHighCellResistance ? 1 << 17 : 0); // 0x00020000
+ bitfield |= (bmsDclTemperature ? 1 << 18 : 0); // 0x00040000
+ bitfield |= (bmsDclLowCellVoltage ? 1 << 19 : 0); // 0x00080000
+ bitfield |= (bmsDclLowPackVoltage ? 1 << 20 : 0); // 0x00100000
+ bitfield |= (bmsDclCclVoltageFailsafe ? 1 << 21 : 0); // 0x00200000
+ bitfield |= (bmsDclCclCommunication ? 1 << 22 : 0); // 0x00400000
+ bitfield |= (bmsCclHighSoc ? 1 << 23 : 0); // 0x00800000
+ bitfield |= (bmsCclHighCellResistance ? 1 << 24 : 0); // 0x01000000
+ bitfield |= (bmsCclTemperature ? 1 << 25 : 0); // 0x02000000
+ bitfield |= (bmsCclHighCellVoltage ? 1 << 26 : 0); // 0x04000000
+ bitfield |= (bmsCclHighPackVoltage ? 1 << 27 : 0); // 0x08000000
+ bitfield |= (bmsCclChargerLatch ? 1 << 28 : 0); // 0x10000000
+ bitfield |= (bmsCclAlternate ? 1 << 29 : 0); // 0x20000000
+// bitfield |= (reserve ? 1 << 30 : 0); // 0x40000000
+// bitfield |= (reserve ? 1 << 31 : 0); // 0x80000000
+
+ return bitfield;
+}
+
+/*
+ * Calculate the bit field 3 from the respective flags for faster transmission
+ * to the web site.
+ *
+ * Bitfield contains information about the digital inputs/outputs
+ */
+uint32_t Status::getBitFieldIO() {
+ uint32_t bitfield = 0;
+
+ bitfield |= (brakeHold ? 1 << 0 : 0); // 0x00000001
+ bitfield |= (preChargeRelay ? 1 << 1 : 0); // 0x00000002
+ bitfield |= (secondaryContactor ? 1 << 2 : 0); // 0x00000004
+ bitfield |= (mainContactor ? 1 << 3 : 0); // 0x00000008
+ bitfield |= (enableMotor ? 1 << 4 : 0); // 0x00000010
+ bitfield |= (coolingFan ? 1 << 5 : 0); // 0x00000020
+ bitfield |= (brakeLight ? 1 << 6 : 0); // 0x00000040
+ bitfield |= (reverseLight ? 1 << 7 : 0); // 0x00000080
+ bitfield |= (enableIn ? 1 << 8 : 0); // 0x00000100
+ bitfield |= (absActive ? 1 << 9 : 0); // 0x00000200
+// bitfield |= (reserve ? 1 << 10 : 0); // 0x00000400
+// bitfield |= (reserve ? 1 << 11 : 0); // 0x00000800
+// bitfield |= (reserve ? 1 << 12 : 0); // 0x00001000
+// bitfield |= (reserve ? 1 << 13 : 0); // 0x00002000
+// bitfield |= (reserve ? 1 << 14 : 0); // 0x00004000
+// bitfield |= (reserve ? 1 << 15 : 0); // 0x00008000
+// bitfield |= (reserve ? 1 << 16 : 0); // 0x00010000
+// bitfield |= (reserve ? 1 << 17 : 0); // 0x00020000
+// bitfield |= (reserve ? 1 << 18 : 0); // 0x00040000
+// bitfield |= (reserve ? 1 << 19 : 0); // 0x00080000
+// bitfield |= (reserve ? 1 << 20 : 0); // 0x00100000
+// bitfield |= (reserve ? 1 << 21 : 0); // 0x00200000
+// bitfield |= (reserve ? 1 << 22 : 0); // 0x00400000
+// bitfield |= (reserve ? 1 << 23 : 0); // 0x00800000
+// bitfield |= (reserve ? 1 << 24 : 0); // 0x01000000
+// bitfield |= (reserve ? 1 << 25 : 0); // 0x02000000
+// bitfield |= (reserve ? 1 << 26 : 0); // 0x04000000
+// bitfield |= (reserve ? 1 << 27 : 0); // 0x08000000
+// bitfield |= (reserve ? 1 << 28 : 0); // 0x10000000
+// bitfield |= (reserve ? 1 << 29 : 0); // 0x20000000
+// bitfield |= (reserve ? 1 << 30 : 0); // 0x40000000
+// bitfield |= (reserve ? 1 << 31 : 0); // 0x80000000
+
+ return bitfield;
+}
diff --git a/Status.h b/Status.h
new file mode 100644
index 0000000..8414c64
--- /dev/null
+++ b/Status.h
@@ -0,0 +1,173 @@
+/*
+ * Status.h
+ *
+ *
+ Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
+
+ 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 STATUS_H_
+#define STATUS_H_
+
+#include
+#include "Logger.h"
+#include "Sys_Messages.h"
+
+class Status
+{
+public:
+ enum SystemState
+ {
+ startup = 0, // the system is starting-up (next states: init, error)
+ init = 1, // the system is being initialized and is not ready for operation yet (next states: preCharge, ready, error)
+ preCharge = 2, // the system is initialized and executing the pre-charge cycle (next states: ready, error)
+ preCharged = 3, // the system is pre-charged, the pre-charge cycle is finished
+ batteryHeating = 4, // before charging, the batteries need to be heated
+ charging = 5, // the batteries are being charged
+ charged = 6, // the charging is finished
+ ready = 7, // the system is ready to accept commands but the motor controller is not enabled yet (next states: running, error)
+ running = 8, // the system is running and the motor controller is to be enabled (next states: ready, error)
+ shutdown = 9, // the system is shutdown and must be restarted to get operational again
+ error = 99 // the system is in an error state and not operational (no power on motor, turn of power stage)
+ };
+
+ // power limitation flags
+ bool limitationTorque; // a general indicator that torque is limited by one or more limiters
+ bool limitationMaxTorque; // torque limitation active due to configured/allowed maximum torque
+ bool limitationSpeed; // torque limitation active due to configured maximum speed
+ bool limitationControllerTemperature; // torque limitation active due to high temperature of the motor controller
+ bool limitationMotorTemperature; // torque limitation active due to high motor temperature
+ bool limitationSlewRate; // torque limitation active due to configured torque/speed slew rate
+ bool limitationMotorModel; // torque limitation active due to the motor model
+ bool limitationMechanicalPower; // torque limitation active due to configured maximum mechanical power
+ bool limitationAcVoltage; // torque limitation active due to configured maximum AC voltage
+ bool limitationAcCurrent; // torque limitation active due to configured maximum AC current
+ bool limitationDcVoltage; // torque limitation active due to configured DC voltage limits
+ bool limitationDcCurrent; // torque limitation active due to configured DC current limits (motoring or regenerating)
+
+ // warning flags
+ bool warning; // a general warning condition is present but the system could still be/become operational
+ bool oscillationLimiter; // the oscillation limiter of the motor controller is active to dampen oscillations in the requested torque
+ bool maximumModulationLimiter; // the motor's maximum modulation limiter is active
+ bool systemCheckActive; // is the system not ready yet because of a system check?
+
+ // error flags
+ bool overtempController; // severe over temperature in motor controller
+ bool overtempMotor; // severe over temperature in motor
+ bool overspeed; // over speed detected
+ bool hvUndervoltage; // the HV voltage dropped below the motor controller's limits
+ bool hvOvervoltage; // the HV voltage exceeded the motor controller's limits
+ bool hvOvercurrent; // the HV current exceeded the motor controller's limits
+ bool acOvercurrent; // the demanded AC current would exceed / exceeds the allowed maximum current
+
+ bool brakeHold; // is brake hold acitve ?
+ bool preChargeRelay; // is the pre-charge relay activated ?
+ bool mainContactor; // is the main contactor relay activated ?
+ bool secondaryContactor; // is the secondary relay activated ?
+ bool fastChargeContactor; // is the secondary relay activated ?
+
+ bool enableMotor; // is the 'enable' output activated ?
+ bool enableCharger; // is the charger (relay) activated ?
+ bool enableDcDc; // is the dc dc (relay) activated ?
+ bool enableHeater; // is the heater (relay) activated ?
+
+ bool heaterValve; // is the heater valve relay enabled (battery / cabin heating)?
+ bool heaterPump; // is the heater pump relay enabled ?
+ bool coolingPump; // is the cooling pump relay activated ?
+ bool coolingFan; // is the cooling relay activated ?
+
+ bool brakeLight; // is the brake light relay activated ?
+ bool reverseLight; // is the reverse light relay activated ?
+ bool powerSteering; // is the power steering activated ?
+ bool unused; // is the ... activated ?
+
+ bool enableIn; // is the 'enable' input signal active ?
+ bool chargePowerAvailable; // is shore power available (connected to charging station)
+ bool interlockPresent; // is the interlock circuit closed and the signal available ?
+ bool reverseInput; // is the reverse signal present ?
+ bool absActive; // is ABS or another source active to disable any power output to the motor
+ bool gearChangeActive; // is a gear change in progress ?
+ bool enableRegen; // is regen currently activated ?
+ bool enableCreep; // is creep activated ?
+
+ uint8_t stateOfCharge; // state of charge (in 0.5%)
+ uint32_t flowCoolant; // ml per second coolant flow
+ uint32_t flowHeater; // ml per second heater flow
+ uint8_t statusLight; // 0 to 255 for the PWM of the status light
+
+ bool digitalInput[CFG_NUMBER_DIGITAL_INPUTS]; // the the digital input x activated ?
+ bool digitalOutput[CFG_NUMBER_DIGITAL_OUTPUTS]; // the the digital output x activated ?
+
+ int16_t temperatureBattery[CFG_NUMBER_BATTERY_TEMPERATURE_SENSORS]; // temperature reported via CAN from external device
+ int16_t temperatureCoolant; // temperature of the coolant water, reported via CAN from GEVCU extension
+ int16_t heaterTemperature; // temperature of the heater water, calculated from analog input
+ int16_t temperatureExterior; // exterior temperature (ambient) reported via CAN from GEVCU extension
+ uint16_t heaterPower; // the power of the heater in Watt
+ uint8_t vehicleSpeed; // vehicle speed in kmh
+ uint8_t barometricPressure; // barometric pressure in kPa
+ bool dcdcRunning; // is the dcdc converter running ? (true if no dcdc converter is enabled)
+
+ bool bmsDclLowSoc; //DischargeLimit Reduced Due To Low SOC
+ bool bmsDclHighCellResistance; //DischargeLimit Reduced Due To High Cell Resistance
+ bool bmsDclTemperature; //DischargeLimit Reduced Due To Temperature
+ bool bmsDclLowCellVoltage; //DischargeLimit Reduced Due To Low Cell Voltage
+ bool bmsDclLowPackVoltage; //DischargeLimit Reduced Due To Low Pack Voltage
+ bool bmsDclCclVoltageFailsafe; //DischargeLimit and ChargeLimit Reduced Due To Voltage Failsafe
+ bool bmsDclCclCommunication; //DischargeLimit and ChargeLimit Reduced Due To Communication Failsafe: This only applies if there are multiple BMS units connected together in series over CANBUS.
+ bool bmsCclHighSoc; //ChargeLimit Reduced Due To High SOC
+ bool bmsCclHighCellResistance; //ChargeLimit Reduced Due To High Cell Resistance
+ bool bmsCclTemperature; //ChargeLimit Reduced Due To Temperature
+ bool bmsCclHighCellVoltage; //ChargeLimit Reduced Due To High Cell Voltage
+ bool bmsCclHighPackVoltage; //ChargeLimit Reduced Due To High Pack Voltage
+ bool bmsCclChargerLatch; //ChargeLimit Reduced Due To Charger Latch): This means the ChargeLimit is likely 0A because the charger has been turned off. This latch is removed when the Charge Power signal is removed and re-applied (ie: unplugging the car and plugging it back in).
+ bool bmsCclAlternate; //ChargeLimit Reduced Due To Alternate Current Limit [MPI]
+ bool bmsRelayDischarge; // Discharge relay enabled
+ bool bmsRelayCharge; // Charge relay enabled
+ bool bmsChagerSafety; // Charger safety enabled
+ bool bmsDtcPresent; // Malfunction indicator active (DTC status)
+ bool bmsVoltageFailsafe;
+ bool bmsCurrentFailsafe;
+ bool bmsDepleted;
+ bool bmsBalancingActive;
+ bool bmsDtcWeakCellFault;
+ bool bmsDtcLowCellVolage;
+ bool bmsDtcHVIsolationFault;
+ bool bmsDtcVoltageRedundancyFault;
+ uint32_t stateTimestamp; // time stamp of last state change
+
+ Status();
+ SystemState getSystemState();
+ SystemState setSystemState(SystemState);
+ String systemStateToStr(SystemState);
+ uint32_t getBitFieldMotor();
+ uint32_t getBitFieldBms();
+ uint32_t getBitFieldIO();
+ int16_t getLowestBatteryTemperature();
+ int16_t getHighestBatteryTemperature();
+
+private:
+ SystemState systemState; // the current state of the system, to be modified by the state machine of this class only
+};
+
+extern Status status;
+
+#endif /* STATUS_H_ */
diff --git a/StatusIndicator.cpp b/StatusIndicator.cpp
new file mode 100644
index 0000000..1d8a348
--- /dev/null
+++ b/StatusIndicator.cpp
@@ -0,0 +1,164 @@
+/*
+ * StatusIndicator.cpp
+ *
+ Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
+
+ 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 "StatusIndicator.h"
+
+StatusIndicator::StatusIndicator() :
+ Device()
+{
+ prefsHandler = new PrefHandler(STATUSINDICATOR);
+ commonName = "Status Display";
+ step = 0;
+ increment = false;
+ cfg.cyclesDown = cfg.cyclesUp = 1;
+}
+
+void StatusIndicator::setup()
+{
+ Device::setup();
+
+ systemIO.setStatusLight(0);
+ ready = true;
+ running = true;
+}
+
+void StatusIndicator::handleTick()
+{
+ step += (increment ? cfg.increment : -cfg.decrement);
+ if (step > 250) {
+ increment = false;
+ step = 250;
+ if (cfg.cyclesUp > 0) {
+ cfg.cyclesUp--;
+ }
+ }
+ if (step < 1) {
+ increment = true;
+ step = 0;
+ if (cfg.cyclesDown > 0) {
+ cfg.cyclesDown--;
+ }
+ }
+ systemIO.setStatusLight(1 / (1 + exp(((step / 20.0f) - 8) * -0.75f)) * cfg.maxLevel + cfg.minLevel);
+
+ if ((increment && cfg.cyclesUp == 0) || (!increment && cfg.cyclesDown == 0)) {
+ tickHandler.detach(this);
+ systemIO.setStatusLight((increment ? cfg.minLevel : cfg.maxLevel));
+ }
+}
+
+/**
+ * \brief Act on system state changes
+ *
+ * \param oldState the previous system state
+ * \param newState the new system state
+ */
+void StatusIndicator::handleStateChange(Status::SystemState oldState, Status::SystemState newState)
+{
+ Device::handleStateChange(oldState, newState);
+
+ switch (newState) {
+ case Status::init:
+ case Status::charged:
+ handleMessage(MSG_UPDATE, (void *) "pulse");
+ break;
+ case Status::charging:
+ handleMessage(MSG_UPDATE, (void *) "blink");
+ break;
+ case Status::running:
+ handleMessage(MSG_UPDATE, (void *) "on");
+ break;
+ default:
+ break;
+ }
+}
+
+void StatusIndicator::handleMessage(uint32_t messageType, void* message)
+{
+ Device::handleMessage(messageType, message);
+
+ switch (messageType) {
+ case MSG_UPDATE: {
+ char *param = (char *) message;
+
+ if (!strcmp("on", param)) {
+ setMode(220, 0, 5, 5, 1, 0);
+ increment = true;
+ } else if (!strcmp("off", param)) {
+ setMode(220, 0, 3, 3, 0, 1);
+ increment = false;
+ } else if (!strcmp("blink", param)) {
+ setMode(220, 6, 4, 3, -1, -1);
+ } else if (!strcmp("pulse", param)) {
+ setMode(45, 4, 1, 1, -1, -1);
+ }
+ break;
+ }
+ }
+}
+
+void StatusIndicator::setMode(uint8_t maxLevel, uint8_t minLevel, uint8_t increment, uint8_t decrement, int16_t cyclesUp, int16_t cyclesDown)
+{
+ cfg.maxLevel = maxLevel;
+ cfg.minLevel = minLevel;
+ cfg.increment = increment;
+ cfg.decrement = decrement;
+ cfg.cyclesUp = cyclesUp;
+ cfg.cyclesDown = cyclesDown;
+
+ if (!tickHandler.isAttached(this, CFG_TICK_INTERVAL_STATUS)) {
+ tickHandler.attach(this, CFG_TICK_INTERVAL_STATUS);
+ }
+}
+
+DeviceType StatusIndicator::getType()
+{
+ return DEVICE_DISPLAY;
+}
+
+DeviceId StatusIndicator::getId()
+{
+ return STATUSINDICATOR;
+}
+
+void StatusIndicator::loadConfiguration()
+{
+// StatusDisplayConfiguration *config = (StatusDisplayConfiguration *) getConfiguration();
+
+ if (prefsHandler->checksumValid()) { //checksum is good, read in the values stored in EEPROM
+// prefsHandler->read(EESYS_, &config->);
+ } else {
+ saveConfiguration();
+ }
+}
+
+void StatusIndicator::saveConfiguration()
+{
+// StatusDisplayConfiguration *config = (StatusDisplayConfiguration *) getConfiguration();
+
+// prefsHandler->write(EESYS_, config->);
+ prefsHandler->saveChecksum();
+}
diff --git a/CanPIDListener.h b/StatusIndicator.h
similarity index 58%
rename from CanPIDListener.h
rename to StatusIndicator.h
index 1b3b81b..0d01fc7 100644
--- a/CanPIDListener.h
+++ b/StatusIndicator.h
@@ -1,5 +1,5 @@
/*
- * CanPidListener.h
+ * StatusIndicator.h
*
Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
@@ -24,44 +24,46 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
*/
-#ifndef CAN_PID_H_
-#define CAN_PID_H_
+#ifndef STATUSINDICATOR_H_
+#define STATUSINDICATOR_H_
-#include
#include "config.h"
-#include "Throttle.h"
-#include "DeviceManager.h"
#include "TickHandler.h"
-#include "CanHandler.h"
-#include "constants.h"
-
+#include "DeviceManager.h"
+#include "SystemIO.h"
+#include "Status.h"
-class CanPIDConfiguration : public DeviceConfiguration {
+class IndicatorConfig {
public:
- uint32_t pidId; //what ID are we listening for?
- uint32_t pidMask;
- bool useExtended;
+ uint8_t maxLevel;
+ uint8_t minLevel;
+ uint8_t increment;
+ uint8_t decrement;
+ int16_t cyclesUp;
+ int16_t cyclesDown;
};
-class CanPIDListener: public Device, CanObserver {
+class StatusIndicator: public Device
+{
public:
- CanPIDListener();
- void setup();
- void handleTick();
- void handleCanFrame(CAN_FRAME *frame);
- DeviceId getId();
+ StatusIndicator();
+ void setup();
+ void handleTick();
+ void handleStateChange(Status::SystemState oldState, Status::SystemState newState);
+ void handleMessage(uint32_t messageType, void* message);
+ DeviceType getType();
+ DeviceId getId();
- void loadConfiguration();
- void saveConfiguration();
+ void loadConfiguration();
+ void saveConfiguration();
protected:
private:
- uint32_t responseId; // the CAN id with which the response is sent;
- uint32_t responseMask; // the mask for the responseId
- bool responseExtended; // if the response is expected as an extended frame
- bool processShowData(CAN_FRAME* inFrame, CAN_FRAME& outFrame);
- bool processShowCustomData(CAN_FRAME* inFrame, CAN_FRAME& outFrame);
+ int16_t step;
+ boolean increment;
+ IndicatorConfig cfg;
+ void setMode(uint8_t maxLevel, uint8_t minLevel, uint8_t increment, uint8_t decrement, int16_t cyclesUp, int16_t cyclesDown);
};
-#endif //CAN_PID_H_
\ No newline at end of file
+#endif /* STATUSINDICATOR_H_ */
diff --git a/Sys_Messages.h b/Sys_Messages.h
index 2034418..1e7cbd8 100644
--- a/Sys_Messages.h
+++ b/Sys_Messages.h
@@ -26,16 +26,20 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
#ifndef SYSMSG_H_
#define SYSMSG_H_
-
-enum SystemMessage {
- MSG_STARTUP = 0x3000,
- MSG_SOFT_FAULT = 0x3100,
- MSG_HARD_FAULT = 0x3150,
- MSG_DISABLE = 0x3200,
- MSG_ENABLE = 0x3300,
- MSG_SET_PARAM = 0x4000,
- MSG_CONFIG_CHANGE = 0x4001,
- MSG_COMMAND = 0x4002
+enum SystemMessage
+{
+ MSG_SOFT_FAULT = 0x3100,
+ MSG_HARD_FAULT = 0x3150,
+ MSG_DISABLE = 0x3200,
+ MSG_ENABLE = 0x3300,
+ MSG_SET_PARAM = 0x4000,
+ MSG_CONFIG_CHANGE = 0x4001,
+ MSG_COMMAND = 0x4002,
+ MSG_STATE_CHANGE = 0x4003,
+ MSG_UPDATE = 0x4004,
+ MSG_RESET = 0x4005,
+ MSG_LOG = 0x4006,
+ MSG_KILL = 0x4007
};
#endif
diff --git a/SystemIO.cpp b/SystemIO.cpp
new file mode 100644
index 0000000..b6f4fc3
--- /dev/null
+++ b/SystemIO.cpp
@@ -0,0 +1,1281 @@
+/*
+ * SystemIO.cpp
+ *
+ * Handles the low level details of system I/O
+ *
+ Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
+
+ 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.
+
+ some portions based on code credited as:
+ Arduino Due ADC->DMA->USB 1MSPS
+ by stimmer
+
+ */
+
+#include "SystemIO.h"
+#include "DeviceManager.h"
+
+#undef HID_ENABLED
+
+SystemIO systemIO;
+
+/*
+ * Constructor
+ */
+SystemIO::SystemIO() {
+ configuration = new SystemIOConfiguration();
+ prefsHandler = NULL;
+ preChargeStart = 0;
+ useRawADC = false;
+ deactivatedPowerSteering = false;
+ deactivatedHeater = false;
+}
+
+SystemIO::~SystemIO() {
+}
+
+void SystemIO::setup() {
+ tickHandler.detach(this);
+
+ if (prefsHandler == NULL) {
+ prefsHandler = new PrefHandler(SYSTEM); // must not be instantiated in the constructor because this class is stack instantiated (pref/memcache are not ready in the contructor)
+ }
+
+ loadConfiguration();
+
+ initializePinTables();
+ initializeDigitalIO();
+ initializeAnalogIO();
+ printIOStatus();
+
+ tickHandler.attach(this, CFG_TICK_INTERVAL_SYSTEM_IO);
+}
+
+void SystemIO::handleTick() {
+ if (!handleState()) {
+ return;
+ }
+
+ BatteryManager *batteryManager = deviceManager.getBatteryManager();
+ if (batteryManager != NULL && batteryManager->hasSoc()) {
+ setStateOfCharge(batteryManager->getSoc());
+ }
+
+ handleCooling();
+ handleCharging();
+ handleBrakeLight();
+ handleReverseLight();
+ handleHighPowerDevices();
+
+ updateDigitalInputStatus();
+}
+
+bool SystemIO::handleState() {
+ Status::SystemState state = status.getSystemState();
+
+ if (state == Status::error) {
+ powerDownSystem();
+ return false;
+ }
+
+ if (!isInterlockPresent()) {
+ logger.error("Interlock circuit open - security risk, disabling HV !!");
+ state = status.setSystemState(Status::error);
+ }
+
+ if (isEnableSignalPresent()) {
+ // if the system is ready and the enable input is high, then switch to state "running", this should enable the motor controller
+ if (state == Status::ready) {
+ state = status.setSystemState(Status::running);
+
+ // also check if exterior temperature is low and we need to auto-enable the heater
+ if (status.temperatureExterior <= configuration->heaterTemperatureOn) {
+ systemIO.setEnableHeater(true);
+ systemIO.setHeaterPump(true);
+ }
+ setPowerSteering(true);
+ }
+ } else {
+ // if enable input is low and the motor controller is running, then disable it by switching to state "ready"
+ if (state == Status::running) {
+ state = status.setSystemState(Status::ready);
+ }
+ }
+
+ if (state == Status::preCharge) {
+ handlePreCharge();
+ }
+
+ if (state == Status::preCharged) {
+ state = status.setSystemState(Status::ready);
+ }
+
+ // don't let the heater or power steering running
+ if (state != Status::running) {
+ if (status.enableHeater && state != Status::batteryHeating && state != Status::charging &&
+ state != Status::charged && state != Status::ready) {
+ systemIO.setEnableHeater(false);
+ systemIO.setHeaterPump(false);
+ }
+ if (status.powerSteering) {
+ systemIO.setPowerSteering(false);
+ }
+ }
+
+ return true;
+}
+
+/*
+ * Update the status flags so the input signal can be monitored in the status web page.
+ */
+void SystemIO::updateDigitalInputStatus() {
+ status.digitalInput[0] = getDigitalIn(0);
+ status.digitalInput[1] = getDigitalIn(1);
+ status.digitalInput[2] = getDigitalIn(2);
+ status.digitalInput[3] = getDigitalIn(3);
+}
+
+/**
+ * Perform the necessary steps to power down the system (incl. HV contactors).
+ */
+void SystemIO::powerDownSystem() {
+ setPrechargeRelay(false);
+ setMainContactor(false);
+ setSecondaryContactor(false);
+ setFastChargeContactor(false);
+
+ setEnableMotor(false);
+ setEnableCharger(false);
+ setEnableDcDc(false);
+ setEnableHeater(false);
+
+ setHeaterValve(false);
+ setHeaterPump(false);
+ setCoolingPump(false);
+ setCoolingFan(false);
+
+ setBrakeLight(false);
+ setReverseLight(false);
+ setPowerSteering(false);
+ setUnused(false);
+
+ setWarning(false);
+ setPowerLimitation(false);
+}
+
+/*
+ * Handle the pre-charge sequence.
+ */
+void SystemIO::handlePreCharge() {
+ if (configuration->prechargeMillis == 0) { // we don't want to pre-charge
+ logger.info("Pre-charging not enabled");
+ setMainContactor(true);
+ status.setSystemState(Status::preCharged);
+ return;
+ }
+
+ if (preChargeStart == 0) {
+ if (millis() > CFG_PRE_CHARGE_START) {
+ logger.info("Starting pre-charge sequence");
+ printIOStatus();
+
+ preChargeStart = millis();
+ setPrechargeRelay(true);
+
+#ifdef CFG_THREE_CONTACTOR_PRECHARGE
+ delay(CFG_PRE_CHARGE_RELAY_DELAY);
+ setSecondaryContactor(true);
+#endif
+ }
+ } else {
+ logPreCharge();
+ if ((millis() - preChargeStart) > configuration->prechargeMillis) {
+ setMainContactor(true);
+ delay(CFG_PRE_CHARGE_RELAY_DELAY);
+ setPrechargeRelay(false);
+
+ status.setSystemState(Status::preCharged);
+ logger.info("Pre-charge sequence complete after %i milliseconds", millis() - preChargeStart);
+ }
+ }
+}
+
+/**
+ * Print the voltages reported by the devices during a pre-charge cycle
+ */
+void SystemIO::logPreCharge() {
+ uint16_t voltsMotor = 0, voltsDcDc = 0, voltsBms = 0;
+ if (deviceManager.getMotorController())
+ voltsMotor = deviceManager.getMotorController()->getDcVoltage();
+ if (deviceManager.getDcDcConverter())
+ voltsDcDc = deviceManager.getDcDcConverter()->getHvVoltage();
+ if (deviceManager.getBatteryManager())
+ voltsBms = deviceManager.getBatteryManager()->getPackVoltage();
+ logger.info("pre-charge info: time: %dms, motor: %dV, dcdc: %dV, bms: %dV", millis() - preChargeStart, voltsMotor, voltsDcDc, voltsBms);
+}
+
+/**
+ * Perform a 10 sec pre-charge cycle and print out voltages reported by the devices
+ */
+void SystemIO::measurePreCharge() {
+ setPrechargeRelay(true);
+ logger.info("closing pre-charge relay");
+#ifdef CFG_THREE_CONTACTOR_PRECHARGE
+ delay(CFG_PRE_CHARGE_RELAY_DELAY);
+ setSecondaryContactor(true);
+ logger.info("closing secondary contactor");
+#endif
+ preChargeStart = millis();
+ while (millis() < preChargeStart + 10000) {
+ tickHandler.process();
+ canHandlerEv.process();
+ canHandlerCar.process();
+
+ logPreCharge();
+ }
+ status.setSystemState(Status::shutdown);
+}
+
+/*
+ * Control an optional cooling fan output depending on the temperature of
+ * the motor controller
+ */
+void SystemIO::handleCooling() {
+ MotorController *motorController = deviceManager.getMotorController();
+ DcDcConverter *dcdcConverter = deviceManager.getDcDcConverter();
+ Status::SystemState state = status.getSystemState();
+
+ if (state == Status::ready || state == Status::running ||
+ (dcdcConverter != NULL && dcdcConverter->isRunning() && dcdcConverter->getTemperature() > 400)) {
+ if (!status.coolingPump) {
+ setCoolingPump(true);
+ }
+ } else {
+ if (status.coolingPump && (dcdcConverter == NULL || !dcdcConverter->isRunning() || dcdcConverter->getTemperature() < 350)) {
+ setCoolingPump(false);
+ }
+ }
+
+ if (motorController) {
+ if (motorController->getTemperatureController() == CFG_NO_TEMPERATURE_DATA) {
+ return;
+ }
+
+ if (motorController->getTemperatureController() / 10 > configuration->coolingTempOn && !status.coolingFan && status.dcdcRunning) {
+ setCoolingFan(true);
+ }
+
+ if (motorController->getTemperatureController() / 10 < configuration->coolingTempOff && status.coolingFan) {
+ setCoolingFan(false);
+ }
+ }
+}
+
+/*
+ * Verify if we're connected to a charge station and handle the charging process
+ * (including an evtl. heating period for the batteries)
+ */
+void SystemIO::handleCharging() {
+ Status::SystemState state = status.getSystemState();
+
+ if (isChargePowerAvailable()) { // we're connected to "shore" power
+ if (state == Status::running) {
+ state = status.setSystemState(Status::ready);
+ }
+ if (state == Status::ready || state == Status::batteryHeating) {
+ int16_t batteryTemp = status.getLowestBatteryTemperature();
+ if (batteryTemp == CFG_NO_TEMPERATURE_DATA || batteryTemp >= CFG_MIN_BATTERY_CHARGE_TEMPERATURE) {
+ state = status.setSystemState(Status::charging);
+ } else {
+ state = status.setSystemState(Status::batteryHeating);
+ }
+ }
+ if (state == Status::charged && (status.stateTimestamp + CFG_CHARGED_SHUTDOWN_TIME < millis())) {
+ state = status.setSystemState(Status::shutdown);
+ powerDownSystem();
+ }
+ } else {
+ // terminate all charge related activities and return to ready if GEVCU is still powered on
+ if (state == Status::charging || state == Status::charged || state == Status::batteryHeating) {
+ state = status.setSystemState(Status::ready);
+ }
+ }
+}
+
+/**
+ * Turn on/off the brake light at a configured level of actual torque
+ */
+void SystemIO::handleBrakeLight() {
+ MotorController *motorController = deviceManager.getMotorController();
+
+ if (motorController && motorController->getTorqueActual() < CFG_TORQUE_BRAKE_LIGHT_ON) {
+ if (!status.brakeLight) {
+ setBrakeLight(true); //Turn on brake light output
+ }
+ } else {
+ if (status.brakeLight) {
+ setBrakeLight(false); //Turn off brake light output
+ }
+ }
+}
+
+/**
+ * Turn on/off the reverse light if we're in reverse mode.
+ */
+void SystemIO::handleReverseLight() {
+ MotorController *motorController = deviceManager.getMotorController();
+
+ if (motorController && motorController->getGear() == MotorController::GEAR_REVERSE) {
+ if (!status.reverseLight) {
+ setReverseLight(true);
+ }
+ } else {
+ if (status.reverseLight) {
+ setReverseLight(false);
+ }
+ }
+}
+
+/**
+ * Shut-Down high power devices in case the DCDC converter is not running and power them back on
+ * once the converter is running
+ */
+void SystemIO::handleHighPowerDevices() {
+ if (status.dcdcRunning) {
+ if (deactivatedHeater) {
+ deactivatedHeater = false;
+ setEnableHeater(true);
+ setHeaterPump(true);
+ }
+ if (deactivatedPowerSteering) {
+ deactivatedPowerSteering = false;
+ setPowerSteering(true);
+ }
+ } else {
+ if (status.enableHeater) {
+ deactivatedHeater = true;
+ setEnableHeater(false);
+ setHeaterPump(false);
+ }
+ if (status.powerSteering) {
+ deactivatedPowerSteering = true;
+ setPowerSteering(false);
+ }
+ }
+}
+
+/*
+ * Get the the input signal for the car's enable signal.
+ */
+bool SystemIO::isEnableSignalPresent() {
+ bool flag = getDigitalIn(configuration->enableInput);
+ status.enableIn = flag;
+ return flag;
+}
+
+/*
+ * Get the the input signal which indicates if the car is connected to a charge station
+ */
+bool SystemIO::isChargePowerAvailable() {
+ bool flag = getDigitalIn(configuration->chargePowerAvailableInput);
+ status.chargePowerAvailable = flag;
+ return flag;
+}
+
+/*
+ * Get the the input signal which indicates if the car is connected to a charge station
+ */
+bool SystemIO::isInterlockPresent() {
+ // if not configured, return true in order not to power-down the system
+ if (configuration->interlockInput == CFG_OUTPUT_NONE) {
+ return true;
+ }
+
+ bool flag = getDigitalIn(configuration->interlockInput);
+ status.interlockPresent = flag;
+ return flag;
+}
+
+/*
+ * Get the the input signal which indicates if the car is connected to a charge station
+ */
+bool SystemIO::isReverseSignalPresent() {
+ bool flag = getDigitalIn(configuration->reverseInput);
+ status.reverseInput = flag;
+ return flag;
+}
+
+/*
+ * Get the input signal which indicates if the car's ABS is active (car skidding -> no torque)
+ */
+bool SystemIO::isABSActive() {
+ bool flag = getDigitalIn(configuration->absInput);
+ status.absActive = flag;
+ return flag;
+}
+
+/*
+ * Get the input signal which indicates that a gear change is in progress (e.g. by switch on gear stick) - to adjust motor speed
+ */
+bool SystemIO::isGearChangeActive() {
+ bool flag = getDigitalIn(configuration->gearChangeInput);
+ status.gearChangeActive = flag;
+ return flag;
+}
+
+/*
+ * Enable / disable the pre-charge relay output and set the status flag.
+ */
+void SystemIO::setPrechargeRelay(bool enabled) {
+ setDigitalOut(configuration->prechargeRelayOutput, enabled);
+ status.preChargeRelay = enabled;
+ deviceManager.sendMessage(DEVICE_IO, CANIO, MSG_UPDATE, NULL);
+}
+
+/*
+ * Enable / disable the main contactor relay output and set the status flag.
+ */
+void SystemIO::setMainContactor(bool enabled) {
+ setDigitalOut(configuration->mainContactorOutput, enabled);
+ status.mainContactor = enabled;
+ deviceManager.sendMessage(DEVICE_IO, CANIO, MSG_UPDATE, NULL);
+}
+
+/*
+ * Enable / disable the secondary contactor relay output and set the status flag.
+ */
+void SystemIO::setSecondaryContactor(bool enabled) {
+ setDigitalOut(configuration->secondaryContactorOutput, enabled);
+ status.secondaryContactor = enabled;
+ deviceManager.sendMessage(DEVICE_IO, CANIO, MSG_UPDATE, NULL);
+}
+
+/*
+ * Enable / disable the fast charge contactor relay output and set the status flag.
+ */
+void SystemIO::setFastChargeContactor(bool enabled) {
+ setDigitalOut(configuration->fastChargeContactorOutput, enabled);
+ status.fastChargeContactor = enabled;
+ deviceManager.sendMessage(DEVICE_IO, CANIO, MSG_UPDATE, NULL);
+}
+
+/*
+ * Enable / disable the 'enable' relay output and set the status flag.
+ */
+void SystemIO::setEnableMotor(bool enabled) {
+ setDigitalOut(configuration->enableMotorOutput, enabled);
+ status.enableMotor = enabled;
+ deviceManager.sendMessage(DEVICE_IO, CANIO, MSG_UPDATE, NULL);
+}
+
+/*
+ * Enable / disable the charger activation output and set the status flag.
+ */
+void SystemIO::setEnableCharger(bool enabled) {
+ setDigitalOut(configuration->enableChargerOutput, enabled);
+ status.enableCharger = enabled;
+ deviceManager.sendMessage(DEVICE_IO, CANIO, MSG_UPDATE, NULL);
+}
+
+/*
+ * Enable / disable the battery heater output and set the status flag.
+ */
+void SystemIO::setEnableDcDc(bool enabled) {
+ setDigitalOut(configuration->enableDcDcOutput, enabled);
+ status.enableDcDc = enabled;
+ deviceManager.sendMessage(DEVICE_IO, CANIO, MSG_UPDATE, NULL);
+}
+
+/*
+ * Enable / disable the heater output and set the status flag.
+ */
+void SystemIO::setEnableHeater(bool enabled) {
+ setDigitalOut(configuration->enableHeaterOutput, enabled);
+ status.enableHeater = enabled;
+ deviceManager.sendMessage(DEVICE_IO, CANIO, MSG_UPDATE, NULL);
+}
+
+/*
+ * Enable / disable the heating pump output and set the status flag.
+ */
+void SystemIO::setHeaterValve(bool enabled) {
+ setDigitalOut(configuration->heaterValveOutput, enabled);
+ status.heaterValve = enabled;
+ deviceManager.sendMessage(DEVICE_IO, CANIO, MSG_UPDATE, NULL);
+}
+
+/*
+ * Enable / disable the heating pump output and set the status flag.
+ */
+void SystemIO::setHeaterPump(bool enabled) {
+ setDigitalOut(configuration->heaterPumpOutput, enabled);
+ status.heaterPump = enabled;
+ deviceManager.sendMessage(DEVICE_IO, CANIO, MSG_UPDATE, NULL);
+}
+
+/*
+ * Enable / disable the cooling pump output and set the status flag.
+ */
+void SystemIO::setCoolingPump(bool enabled) {
+ setDigitalOut(configuration->coolingPumpOutput, enabled);
+ status.coolingPump = enabled;
+ deviceManager.sendMessage(DEVICE_IO, CANIO, MSG_UPDATE, NULL);
+}
+
+/*
+ * Enable / disable the cooling fan output and set the status flag.
+ */
+void SystemIO::setCoolingFan(bool enabled) {
+ setDigitalOut(configuration->coolingFanOutput, enabled);
+ status.coolingFan = enabled;
+ deviceManager.sendMessage(DEVICE_IO, CANIO, MSG_UPDATE, NULL);
+}
+
+/*
+ * Enable / disable the brake light output and set the status flag.
+ */
+void SystemIO::setBrakeLight(bool enabled) {
+ setDigitalOut(configuration->brakeLightOutput, enabled);
+ status.brakeLight = enabled;
+ deviceManager.sendMessage(DEVICE_IO, CANIO, MSG_UPDATE, NULL);
+}
+
+/*
+ * Enable / disable the brake light output and set the status flag.
+ */
+void SystemIO::setReverseLight(bool enabled) {
+ setDigitalOut(configuration->reverseLightOutput, enabled);
+ status.reverseLight = enabled;
+ deviceManager.sendMessage(DEVICE_IO, CANIO, MSG_UPDATE, NULL);
+}
+
+/*
+ * Enable / disable the power steering output and set the status flag.
+ */
+void SystemIO::setPowerSteering(bool enabled) {
+ setDigitalOut(configuration->powerSteeringOutput, enabled);
+ status.powerSteering = enabled;
+ deviceManager.sendMessage(DEVICE_IO, CANIO, MSG_UPDATE, NULL);
+}
+
+/*
+ * Enable / disable the power steering output and set the status flag.
+ */
+void SystemIO::setUnused(bool enabled) {
+ setDigitalOut(configuration->unusedOutput, enabled);
+ status.unused = enabled;
+ deviceManager.sendMessage(DEVICE_IO, CANIO, MSG_UPDATE, NULL);
+}
+
+/*
+ * Enable / disable the warning light output and set the status flag.
+ */
+void SystemIO::setWarning(bool enabled) {
+ setDigitalOut(configuration->warningOutput, enabled);
+ status.warning = enabled;
+}
+
+/*
+ * Enable / disable the brake light output and set the status flag.
+ */
+void SystemIO::setPowerLimitation(bool enabled) {
+ setDigitalOut(configuration->powerLimitationOutput, enabled);
+ status.limitationTorque = enabled;
+}
+
+/*
+ * Set the value of the estimated state of charge in the range of 0 to 255 (e.g. for a gas tank display)
+ */
+void SystemIO::setStateOfCharge(uint8_t value) {
+ setAnalogOut(configuration->stateOfChargeOutput, value);
+ status.stateOfCharge = value;
+}
+
+/*
+ * Set the PWM value of the status light from 0 to 255
+ */
+void SystemIO::setStatusLight(uint8_t value) {
+ setAnalogOut(configuration->statusLightOutput, value);
+ status.statusLight = value;
+}
+
+/*
+ * Polls for the end of an ADC conversion event. Then processes buffer to extract the averaged
+ * value. It takes this value and averages it with the existing value in an 8 position buffer
+ * which serves as a super fast place for other code to retrieve ADC values.
+ * This is only used when RAWADC is not defined.
+ */
+void SystemIO::ADCPoll() {
+ if (obufn != bufn) {
+ uint32_t tempbuff[8] = { 0, 0, 0, 0, 0, 0, 0, 0 }; //make sure its zero'd
+
+ //the eight or four enabled adcs are interleaved in the buffer
+ //this is a somewhat unrolled for loop with no incrementer. it's odd but it works
+ if (useRawADC) {
+ for (int i = 0; i < 256;) {
+ tempbuff[3] += adcBuffer[obufn][i++];
+ tempbuff[2] += adcBuffer[obufn][i++];
+ tempbuff[1] += adcBuffer[obufn][i++];
+ tempbuff[0] += adcBuffer[obufn][i++];
+ }
+ } else {
+ for (int i = 0; i < 256;) {
+ tempbuff[7] += adcBuffer[obufn][i++];
+ tempbuff[6] += adcBuffer[obufn][i++];
+ tempbuff[5] += adcBuffer[obufn][i++];
+ tempbuff[4] += adcBuffer[obufn][i++];
+ tempbuff[3] += adcBuffer[obufn][i++];
+ tempbuff[2] += adcBuffer[obufn][i++];
+ tempbuff[1] += adcBuffer[obufn][i++];
+ tempbuff[0] += adcBuffer[obufn][i++];
+ }
+ }
+
+ //for (int i = 0; i < 256;i++) logger.debug("%i - %i", i, adcBuf[obufn][i]);
+
+ //now, all of the ADC values are summed over 32/64 readings. So, divide by 32/64 (shift by 5/6) to get the average
+ //then add that to the old value we had stored and divide by two to average those. Lots of averaging going on.
+ if (useRawADC) {
+ for (int j = 0; j < 4; j++) {
+ adcValues[j] += (tempbuff[j] >> 6);
+ adcValues[j] = adcValues[j] >> 1;
+ }
+ } else {
+ for (int j = 0; j < 8; j++) {
+ adcValues[j] += (tempbuff[j] >> 5);
+ adcValues[j] = adcValues[j] >> 1;
+ //logger.debug("A%i: %i", j, adc_values[j]);
+ }
+ }
+
+ for (int i = 0; i < CFG_NUMBER_ANALOG_INPUTS; i++) {
+ int val;
+
+ if (useRawADC) {
+ val = getRawADC(i);
+ } else {
+ val = getDifferentialADC(i);
+ }
+// addNewADCVal(i, val);
+// adc_out_vals[i] = getADCAvg(i);
+ adcOutValues[i] = val;
+ }
+ obufn = bufn;
+ }
+}
+
+/*
+ * Get value of one of the 4 analog inputs.
+ *
+ * Uses a special buffer which has smoothed and corrected ADC values.
+ * This call is very fast because the actual work is done via DMA and
+ * then a separate polled step.
+ */
+uint16_t SystemIO::getAnalogIn(uint8_t which) {
+ if (which >= CFG_NUMBER_ANALOG_INPUTS) {
+ which = 0;
+ }
+ return adcOutValues[which];
+}
+
+/*
+ * Get value of one of the 4 digital inputs.
+ * If input is not configured, false is returned.
+ */
+bool SystemIO::getDigitalIn(uint8_t which) {
+ if (which >= CFG_NUMBER_DIGITAL_INPUTS) {
+ return false;
+ }
+ if (dig[which] == CFG_OUTPUT_NONE) {
+ return false;
+ }
+
+ return !(digitalRead(dig[which]));
+}
+
+/*
+ * Set digital output to high or low.
+ */
+void SystemIO::setDigitalOut(uint8_t which, boolean active) {
+ if (which >= CFG_NUMBER_DIGITAL_OUTPUTS) {
+ return;
+ }
+ if (out[which] == CFG_OUTPUT_NONE) {
+ return;
+ }
+
+ digitalWrite(out[which], active ? HIGH : LOW);
+ status.digitalOutput[which] = active;
+ printIOStatus();
+}
+
+/*
+ * Get current state of digital output (high or low?)
+ */
+bool SystemIO::getDigitalOut(uint8_t which) {
+ if (which >= CFG_NUMBER_DIGITAL_OUTPUTS) {
+ return false;
+ }
+ if (out[which] == 255) {
+ return false;
+ }
+
+ return digitalRead(out[which]);
+}
+
+/*
+ * Set analog output to a specific value (PWM on digital out).
+ */
+void SystemIO::setAnalogOut(uint8_t which, uint8_t value) {
+ if (which >= CFG_NUMBER_DIGITAL_OUTPUTS) {
+ return;
+ }
+ if (out[which] == CFG_OUTPUT_NONE) {
+ return;
+ }
+
+ analogWrite(out[which], value);
+ status.digitalOutput[which] = value != 0;
+ printIOStatus();
+}
+
+/*
+ * Some of the boards are differential and thus require subtracting
+ * one ADC from another to obtain the true value. This function
+ * handles that case. It also applies gain and offset.
+ */
+uint16_t SystemIO::getDifferentialADC(uint8_t which) {
+ uint32_t low, high;
+
+ low = adcValues[adc[which][0]];
+ high = adcValues[adc[which][1]];
+
+ if (low < high) {
+
+ //first remove the bias to bring us back to where it rests at zero input volts
+
+ if (low >= adcComp[which].offset) {
+ low -= adcComp[which].offset;
+ } else {
+ low = 0;
+ }
+
+ if (high >= adcComp[which].offset) {
+ high -= adcComp[which].offset;
+ } else {
+ high = 0;
+ }
+
+ //gain multiplier is 1024 for 1 to 1 gain, less for lower gain, more for higher.
+ low *= adcComp[which].gain;
+ low = low >> 10; //divide by 1024 again to correct for gain multiplier
+ high *= adcComp[which].gain;
+ high = high >> 10;
+
+ //Lastly, the input scheme is basically differential so we have to subtract
+ //low from high to get the actual value
+ high = high - low;
+ } else {
+ high = 0;
+ }
+
+ if (high > 4096) {
+ high = 0; //if it somehow got wrapped anyway then set it back to zero
+ }
+
+ return high;
+}
+
+/*
+ * Exactly like the previous function but for non-differential boards
+ * (all the non-prototype boards are non-differential).
+ */
+uint16_t SystemIO::getRawADC(uint8_t which) {
+ uint32_t val;
+
+ val = adcValues[adc[which][0]];
+
+ //first remove the bias to bring us back to where it rests at zero input volts
+
+ if (val >= adcComp[which].offset) {
+ val -= adcComp[which].offset;
+ } else {
+ val = 0;
+ }
+
+ //gain multiplier is 1024 for 1 to 1 gain, less for lower gain, more for higher.
+ val *= adcComp[which].gain;
+ val = val >> 10; //divide by 1024 again to correct for gain multiplier
+
+ if (val > 4096) {
+ val = 0; //if it somehow got wrapped anyway then set it back to zero
+ }
+
+ return val;
+}
+
+/*
+ * Figure out what hardware we are running on and fill in the pin tables.
+ */
+void SystemIO::initializePinTables() {
+// numberADCSamples = 64;
+ switch (getSystemType()) {
+ case SystemIOConfiguration::GEVCU2:
+ initGevcu2PinTable();
+ break;
+ case SystemIOConfiguration::GEVCU3:
+ initGevcu3PinTable();
+ break;
+ case SystemIOConfiguration::GEVCU4:
+ initGevcu4PinTable();
+ break;
+ default:
+ initGevcuLegacyPinTable();
+ break;
+ }
+
+ if (useRawADC) {
+ logger.info("Using raw ADC mode");
+ }
+}
+
+void SystemIO::initGevcu2PinTable() {
+ logger.info("Running on GEVCU2/DUED hardware.");
+ dig[0] = 9;
+ dig[1] = 11;
+ dig[2] = 12;
+ dig[3] = 13;
+ adc[0][0] = 1;
+ adc[0][1] = 0;
+ adc[1][0] = 3;
+ adc[1][1] = 2;
+ adc[2][0] = 5;
+ adc[2][1] = 4;
+ adc[3][0] = 7;
+ adc[3][1] = 6;
+ out[0] = 52;
+ out[1] = 22;
+ out[2] = 48;
+ out[3] = 32;
+ out[4] = 255;
+ out[5] = 255;
+ out[6] = 255;
+ out[7] = 255;
+ //numberADCSamples = 32;
+}
+
+void SystemIO::initGevcu3PinTable() {
+ logger.info("Running on GEVCU3 hardware");
+ dig[0] = 48;
+ dig[1] = 49;
+ dig[2] = 50;
+ dig[3] = 51;
+ adc[0][0] = 3;
+ adc[0][1] = 255;
+ adc[1][0] = 2;
+ adc[1][1] = 255;
+ adc[2][0] = 1;
+ adc[2][1] = 255;
+ adc[3][0] = 0;
+ adc[3][1] = 255;
+ out[0] = 9;
+ out[1] = 8;
+ out[2] = 7;
+ out[3] = 6;
+ out[4] = 255;
+ out[5] = 255;
+ out[6] = 255;
+ out[7] = 255;
+ useRawADC = true;
+}
+
+void SystemIO::initGevcu4PinTable() {
+ logger.info("Running on GEVCU 4.x hardware");
+ dig[0] = 48;
+ dig[1] = 49;
+ dig[2] = 50;
+ dig[3] = 51;
+ adc[0][0] = 3;
+ adc[0][1] = 255;
+ adc[1][0] = 2;
+ adc[1][1] = 255;
+ adc[2][0] = 1;
+ adc[2][1] = 255;
+ adc[3][0] = 0;
+ adc[3][1] = 255;
+ out[0] = 4;
+ out[1] = 5;
+ out[2] = 6;
+ out[3] = 7;
+ out[4] = 2;
+ out[5] = 3;
+ out[6] = 8;
+ out[7] = 9;
+ useRawADC = true;
+}
+
+void SystemIO::initGevcuLegacyPinTable() {
+ logger.info("Running on legacy hardware?");
+ dig[0] = 11;
+ dig[1] = 9;
+ dig[2] = 13;
+ dig[3] = 12;
+ adc[0][0] = 1;
+ adc[0][1] = 0;
+ adc[1][0] = 2;
+ adc[1][1] = 3;
+ adc[2][0] = 4;
+ adc[2][1] = 5;
+ adc[3][0] = 7;
+ adc[3][1] = 6;
+ out[0] = 52;
+ out[1] = 22;
+ out[2] = 48;
+ out[3] = 32;
+ out[4] = 255;
+ out[5] = 255;
+ out[6] = 255;
+ out[7] = 255;
+// numberADCSamples = 32;
+}
+
+/*
+ * Forces the digital I/O ports to a safe state.
+ */
+void SystemIO::initializeDigitalIO() {
+ int i;
+
+ for (i = 0; i < CFG_NUMBER_DIGITAL_INPUTS; i++) {
+ pinMode(dig[i], INPUT);
+ }
+
+ for (i = 0; i < CFG_NUMBER_DIGITAL_OUTPUTS; i++) {
+ if (out[i] != 255) {
+ pinMode(out[i], OUTPUT);
+ digitalWrite(out[i], LOW);
+ }
+ }
+}
+
+/*
+ * Initialize DMA driven ADC and read in gain/offset for each channel.
+ */
+void SystemIO::initializeAnalogIO() {
+
+ setupFastADC();
+
+ //requires the value to be contiguous in memory
+ for (int i = 0; i < CFG_NUMBER_ANALOG_INPUTS; i++) {
+ adcComp[i].gain = CFG_ADC_GAIN;
+ adcComp[i].offset = CFG_ADC_OFFSET;
+// for (int j = 0; j < numberADCSamples; j++) {
+// adcAverageBuffer[i][j] = 0;
+// }
+//
+// adcPointer[i] = 0;
+ adcValues[i] = 0;
+ adcOutValues[i] = 0;
+ }
+}
+
+/*
+ * Setup the system to continuously read the proper ADC channels and use DMA to place the results into RAM
+ * Testing to find a good batch of settings for how fast to do ADC readings. The relevant areas:
+ * 1. In the adc_init call it is possible to use something other than ADC_FREQ_MAX to slow down the ADC clock
+ * 2. ADC_MR has a clock divisor, start up time, settling time, tracking time, and transfer time. These can be adjusted
+ */
+void SystemIO::setupFastADC() {
+ pmc_enable_periph_clk(ID_ADC);
+ adc_init(ADC, SystemCoreClock, ADC_FREQ_MAX, ADC_STARTUP_FAST); //just about to change a bunch of these parameters with the next command
+
+ /*
+ The MCLK is 12MHz on our boards. The ADC can only run 1MHz so the prescaler must be at least 12x.
+ The ADC should take Tracking+Transfer for each read when it is set to switch channels with each read
+
+ Example:
+ 5+7 = 12 clocks per read 1M / 12 = 83333 reads per second. For newer boards there are 4 channels interleaved
+ so, for each channel, the readings are 48uS apart. 64 of these readings are averaged together for a total of 3ms
+ worth of ADC in each average. This is then averaged with the current value in the ADC buffer that is used for output.
+
+ If, for instance, someone wanted to average over 6ms instead then the prescaler could be set to 24x instead.
+ */
+ ADC->ADC_MR = (1 << 7) //free running
+ + (5 << 8) //12x MCLK divider ((This value + 1) * 2) = divisor
+ + (1 << 16) //8 periods start up time (0=0clks, 1=8clks, 2=16clks, 3=24, 4=64, 5=80, 6=96, etc)
+ + (1 << 20) //settling time (0=3clks, 1=5clks, 2=9clks, 3=17clks)
+ + (4 << 24) //tracking time (Value + 1) clocks
+ + (2 << 28); //transfer time ((Value * 2) + 3) clocks
+
+ if (useRawADC) {
+ ADC->ADC_CHER = 0xF0; //enable A0-A3
+ } else {
+ ADC->ADC_CHER = 0xFF; //enable A0-A7
+ }
+
+ NVIC_EnableIRQ(ADC_IRQn);
+ ADC->ADC_IDR = ~(1 << 27); //dont disable the ADC interrupt for rx end
+ ADC->ADC_IER = 1 << 27; //do enable it
+ ADC->ADC_RPR = (uint32_t) adcBuffer[0]; // DMA buffer
+ ADC->ADC_RCR = 256; //# of samples to take
+ ADC->ADC_RNPR = (uint32_t) adcBuffer[1]; // next DMA buffer
+ ADC->ADC_RNCR = 256; //# of samples to take
+ bufn = obufn = 0;
+ ADC->ADC_PTCR = 1; //enable dma mode
+ ADC->ADC_CR = 2; //start conversions
+
+ logger.debug("Fast ADC Mode Enabled");
+}
+
+void SystemIO::printIOStatus() {
+ if (logger.isDebug()) {
+ logger.debug("AIN0: %d, AIN1: %d, AIN2: %d, AIN3: %d", getAnalogIn(0), getAnalogIn(1), getAnalogIn(2), getAnalogIn(3));
+ logger.debug("DIN0: %d, DIN1: %d, DIN2: %d, DIN3: %d", getDigitalIn(0), getDigitalIn(1), getDigitalIn(2), getDigitalIn(3));
+ logger.debug("DOUT0: %d, DOUT1: %d, DOUT2: %d, DOUT3: %d,DOUT4: %d, DOUT5: %d, DOUT6: %d, DOUT7: %d", getDigitalOut(0), getDigitalOut(1),
+ getDigitalOut(2), getDigitalOut(3), getDigitalOut(4), getDigitalOut(5), getDigitalOut(6), getDigitalOut(7));
+ }
+}
+
+/*
+ * Move DMA pointers to next buffer.
+ */
+uint32_t SystemIO::getNextADCBuffer() {
+ bufn = (bufn + 1) & 3;
+ return (uint32_t) adcBuffer[bufn];
+}
+
+/*
+ * When the ADC reads in the programmed # of readings it will do two things:
+ * 1. It loads the next buffer and buffer size into current buffer and size
+ * 2. It sends this interrupt
+ * This interrupt then loads the "next" fields with the proper values. This is
+ * done with a four position buffer. In this way the ADC is constantly sampling
+ * and this happens virtually for free. It all happens in the background with
+ * minimal CPU overhead.
+ */
+void ADC_Handler() {
+ int f = ADC->ADC_ISR;
+
+ if (f & (1 << 27)) { //receive counter end of buffer
+ ADC->ADC_RNPR = systemIO.getNextADCBuffer();
+ ADC->ADC_RNCR = 256;
+ }
+}
+
+void SystemIO::setSystemType(SystemIOConfiguration::SystemType systemType) {
+ SystemIOConfiguration *config = (SystemIOConfiguration *) getConfiguration();
+ config->systemType = systemType;
+ saveConfiguration();
+}
+SystemIOConfiguration::SystemType SystemIO::getSystemType() {
+ SystemIOConfiguration *config = (SystemIOConfiguration *) getConfiguration();
+ return config->systemType;
+}
+void SystemIO::setCarType(SystemIOConfiguration::CarType carType) {
+ SystemIOConfiguration *config = (SystemIOConfiguration *) getConfiguration();
+ config->carType = carType;
+ saveConfiguration();
+}
+SystemIOConfiguration::CarType SystemIO::getCarType() {
+ SystemIOConfiguration *config = (SystemIOConfiguration *) getConfiguration();
+ return config->carType;
+}
+void SystemIO::setLogLevel(Logger::LogLevel logLevel) {
+ SystemIOConfiguration *config = (SystemIOConfiguration *) getConfiguration();
+ config->logLevel = logLevel;
+ saveConfiguration();
+}
+
+Logger::LogLevel SystemIO::getLogLevel() {
+ SystemIOConfiguration *config = (SystemIOConfiguration *) getConfiguration();
+ return config->logLevel;
+}
+
+/*
+ Adds a new ADC reading to the buffer for a channel. The buffer is NumADCSamples large (either 32 or 64) and rolling
+ */
+//void addNewADCVal(uint8_t which, uint16_t val)
+//{
+// adcAverageBuffer[which][adcPointer[which]] = val;
+// adcPointer[which] = (adcPointer[which] + 1) % numberADCSamples;
+//}
+/*
+ Take the arithmetic average of the readings in the buffer for each channel. This smooths out the ADC readings
+ */
+//uint16_t getADCAvg(uint8_t which)
+//{
+// uint32_t sum;
+// sum = 0;
+//
+// for (int j = 0; j < numberADCSamples; j++) {
+// sum += adcAverageBuffer[which][j];
+// }
+//
+// sum = sum / numberADCSamples;
+// return ((uint16_t) sum);
+//}
+
+SystemIOConfiguration *SystemIO::getConfiguration() {
+ return configuration;
+}
+
+void SystemIO::loadConfiguration() {
+ logger.info("System I/O configuration:");
+
+#ifdef USE_HARD_CODED
+ if (false) {
+#else
+ if (prefsHandler->checksumValid()) { //checksum is good, read in the values stored in EEPROM
+#endif
+ prefsHandler->read(EESIO_ENABLE_INPUT, &configuration->enableInput);
+ prefsHandler->read(EESIO_CHARGE_POWER_AVAILABLE_INPUT, &configuration->chargePowerAvailableInput);
+ prefsHandler->read(EESIO_INTERLOCK_INPUT, &configuration->interlockInput);
+ prefsHandler->read(EESIO_REVERSE_INPUT, &configuration->reverseInput);
+ prefsHandler->read(EESIO_GEAR_CHANGE_INPUT, &configuration->gearChangeInput);
+ prefsHandler->read(EESIO_ABS_INPUT, &configuration->absInput);
+
+ prefsHandler->read(EESIO_PRECHARGE_MILLIS, &configuration->prechargeMillis);
+ prefsHandler->read(EESIO_PRECHARGE_RELAY_OUTPUT, &configuration->prechargeRelayOutput);
+ prefsHandler->read(EESIO_MAIN_CONTACTOR_OUTPUT, &configuration->mainContactorOutput);
+ prefsHandler->read(EESIO_SECONDARY_CONTACTOR_OUTPUT, &configuration->secondaryContactorOutput);
+ prefsHandler->read(EESIO_FAST_CHARGE_CONTACTOR_OUTPUT, &configuration->fastChargeContactorOutput);
+
+ prefsHandler->read(EESIO_ENABLE_MOTOR_OUTPUT, &configuration->enableMotorOutput);
+ prefsHandler->read(EESIO_ENABLE_CHARGER_OUTPUT, &configuration->enableChargerOutput);
+ prefsHandler->read(EESIO_ENABLE_DCDC_OUTPUT, &configuration->enableDcDcOutput);
+ prefsHandler->read(EESIO_ENABLE_HEATER_OUTPUT, &configuration->enableHeaterOutput);
+ prefsHandler->read(EESIO_HEATER_TEMPERATURE_ON, &configuration->heaterTemperatureOn);
+
+ prefsHandler->read(EESIO_HEATER_VALVE_OUTPUT, &configuration->heaterValveOutput);
+ prefsHandler->read(EESIO_HEATER_PUMP_OUTPUT, &configuration->heaterPumpOutput);
+ prefsHandler->read(EESIO_COOLING_PUMP_OUTPUT, &configuration->coolingPumpOutput);
+ prefsHandler->read(EESIO_COOLING_FAN_OUTPUT, &configuration->coolingFanOutput);
+ prefsHandler->read(EESIO_COOLING_TEMP_ON, &configuration->coolingTempOn);
+ prefsHandler->read(EESIO_COOLING_TEMP_OFF, &configuration->coolingTempOff);
+
+ prefsHandler->read(EESIO_BRAKE_LIGHT_OUTPUT, &configuration->brakeLightOutput);
+ prefsHandler->read(EESIO_REVERSE_LIGHT_OUTPUT, &configuration->reverseLightOutput);
+ prefsHandler->read(EESIO_POWER_STEERING_OUTPUT, &configuration->powerSteeringOutput);
+
+ prefsHandler->read(EESIO_WARNING_OUTPUT, &configuration->warningOutput);
+ prefsHandler->read(EESIO_POWER_LIMITATION_OUTPUT, &configuration->powerLimitationOutput);
+ prefsHandler->read(EESIO_STATE_OF_CHARGE_OUTPUT, &configuration->stateOfChargeOutput);
+ prefsHandler->read(EESIO_STATUS_LIGHT_OUTPUT, &configuration->statusLightOutput);
+
+ prefsHandler->read(EESIO_SYSTEM_TYPE, (uint8_t *) &configuration->systemType);
+ prefsHandler->read(EESIO_CAR_TYPE, (uint8_t *) &configuration->carType);
+ prefsHandler->read(EESIO_LOG_LEVEL, (uint8_t *) &configuration->logLevel);
+ logger.setLoglevel((Logger::LogLevel) configuration->logLevel);
+ } else { //checksum invalid. Reinitialize values and store to EEPROM
+ configuration->enableInput = 0;
+ configuration->chargePowerAvailableInput = 1;
+ configuration->interlockInput = CFG_OUTPUT_NONE;
+ configuration->reverseInput = CFG_OUTPUT_NONE;
+ configuration->absInput = CFG_OUTPUT_NONE;
+ configuration->gearChangeInput = CFG_OUTPUT_NONE;
+
+ configuration->prechargeMillis = 3000;
+ configuration->prechargeRelayOutput = 4;
+ configuration->mainContactorOutput = 5;
+ configuration->secondaryContactorOutput = 2;
+ configuration->fastChargeContactorOutput = CFG_OUTPUT_NONE;
+
+ configuration->enableMotorOutput = 3;
+ configuration->enableChargerOutput = CFG_OUTPUT_NONE;
+ configuration->enableDcDcOutput = CFG_OUTPUT_NONE;
+ configuration->enableHeaterOutput = CFG_OUTPUT_NONE;
+ configuration->heaterTemperatureOn = 3;
+
+ configuration->heaterValveOutput = CFG_OUTPUT_NONE;
+ configuration->heaterPumpOutput = CFG_OUTPUT_NONE;
+ configuration->coolingPumpOutput = CFG_OUTPUT_NONE;
+ configuration->coolingFanOutput = CFG_OUTPUT_NONE;
+ configuration->coolingTempOn = 40;
+ configuration->coolingTempOff = 35;
+
+ configuration->brakeLightOutput = CFG_OUTPUT_NONE;
+ configuration->reverseLightOutput = CFG_OUTPUT_NONE;
+ configuration->powerSteeringOutput = CFG_OUTPUT_NONE;
+ configuration->unusedOutput = CFG_OUTPUT_NONE;
+
+ configuration->warningOutput = CFG_OUTPUT_NONE;
+ configuration->powerLimitationOutput = CFG_OUTPUT_NONE;
+ configuration->stateOfChargeOutput = CFG_OUTPUT_NONE;
+ configuration->statusLightOutput = CFG_OUTPUT_NONE;
+
+ configuration->systemType = SystemIOConfiguration::GEVCU4;
+ configuration->carType = SystemIOConfiguration::OBD2;
+ configuration->logLevel = logger.Info;
+
+ saveConfiguration();
+ }
+ logger.info("enable input: %d, charge power avail input: %d, interlock input: %d, reverse input: %d, abs input: %d", configuration->enableInput, configuration->chargePowerAvailableInput, configuration->interlockInput, configuration->reverseInput, configuration->absInput);
+ logger.info("pre-charge milliseconds: %d, pre-charge relay: %d, main contactor: %d, gear change input: %d", configuration->prechargeMillis, configuration->prechargeRelayOutput, configuration->mainContactorOutput, configuration->gearChangeInput);
+ logger.info("secondary contactor: %d, fast charge contactor: %d", configuration->secondaryContactorOutput, configuration->fastChargeContactorOutput);
+ logger.info("enable motor: %d, enable charger: %d, enable DCDC: %d, enable heater: %d, heater temp on: %d deg C", configuration->enableMotorOutput, configuration->enableChargerOutput, configuration->enableDcDcOutput, configuration->enableHeaterOutput, configuration->heaterTemperatureOn);
+ logger.info("heater valve: %d, heater pump: %d", configuration->heaterValveOutput, configuration->heaterPumpOutput);
+ logger.info("cooling pump: %d, cooling fan: %d, cooling temperature ON: %d, cooling tempreature Off: %d", configuration->coolingPumpOutput, configuration->coolingFanOutput, configuration->coolingTempOn, configuration->coolingTempOff);
+ logger.info("brake light: %d, reverse light: %d, power steering: %d, unused: %d", configuration->brakeLightOutput, configuration->reverseLightOutput, configuration->powerSteeringOutput, configuration->unusedOutput);
+ logger.info("warning: %d, power limitation: %d, soc: %d, status: %d", configuration->warningOutput, configuration->powerLimitationOutput, configuration->stateOfChargeOutput, configuration->statusLightOutput);
+ logger.info("sys type: %d, car type: %d, log level: %d", configuration->systemType, configuration->carType, configuration->logLevel);
+}
+
+void SystemIO::saveConfiguration() {
+ prefsHandler->write(EESIO_ENABLE_INPUT, configuration->enableInput);
+ prefsHandler->write(EESIO_CHARGE_POWER_AVAILABLE_INPUT, configuration->chargePowerAvailableInput);
+ prefsHandler->write(EESIO_INTERLOCK_INPUT, configuration->interlockInput);
+ prefsHandler->write(EESIO_REVERSE_INPUT, configuration->reverseInput);
+ prefsHandler->write(EESIO_GEAR_CHANGE_INPUT, configuration->gearChangeInput);
+ prefsHandler->write(EESIO_ABS_INPUT, configuration->absInput);
+
+ prefsHandler->write(EESIO_PRECHARGE_MILLIS, configuration->prechargeMillis);
+ prefsHandler->write(EESIO_PRECHARGE_RELAY_OUTPUT, configuration->prechargeRelayOutput);
+ prefsHandler->write(EESIO_MAIN_CONTACTOR_OUTPUT, configuration->mainContactorOutput);
+ prefsHandler->write(EESIO_SECONDARY_CONTACTOR_OUTPUT, configuration->secondaryContactorOutput);
+ prefsHandler->write(EESIO_FAST_CHARGE_CONTACTOR_OUTPUT, configuration->fastChargeContactorOutput);
+
+ prefsHandler->write(EESIO_ENABLE_MOTOR_OUTPUT, configuration->enableMotorOutput);
+ prefsHandler->write(EESIO_ENABLE_CHARGER_OUTPUT, configuration->enableChargerOutput);
+ prefsHandler->write(EESIO_ENABLE_DCDC_OUTPUT, configuration->enableDcDcOutput);
+ prefsHandler->write(EESIO_ENABLE_HEATER_OUTPUT, configuration->enableHeaterOutput);
+ prefsHandler->write(EESIO_HEATER_TEMPERATURE_ON, configuration->heaterTemperatureOn);
+
+ prefsHandler->write(EESIO_HEATER_VALVE_OUTPUT, configuration->heaterValveOutput);
+ prefsHandler->write(EESIO_HEATER_PUMP_OUTPUT, configuration->heaterPumpOutput);
+ prefsHandler->write(EESIO_COOLING_PUMP_OUTPUT, configuration->coolingPumpOutput);
+ prefsHandler->write(EESIO_COOLING_FAN_OUTPUT, configuration->coolingFanOutput);
+ prefsHandler->write(EESIO_COOLING_TEMP_ON, configuration->coolingTempOn);
+ prefsHandler->write(EESIO_COOLING_TEMP_OFF, configuration->coolingTempOff);
+
+ prefsHandler->write(EESIO_BRAKE_LIGHT_OUTPUT, configuration->brakeLightOutput);
+ prefsHandler->write(EESIO_REVERSE_LIGHT_OUTPUT, configuration->reverseLightOutput);
+ prefsHandler->write(EESIO_POWER_STEERING_OUTPUT, configuration->powerSteeringOutput);
+
+ prefsHandler->write(EESIO_WARNING_OUTPUT, configuration->warningOutput);
+ prefsHandler->write(EESIO_POWER_LIMITATION_OUTPUT, configuration->powerLimitationOutput);
+ prefsHandler->write(EESIO_STATE_OF_CHARGE_OUTPUT, configuration->stateOfChargeOutput);
+ prefsHandler->write(EESIO_STATUS_LIGHT_OUTPUT, configuration->statusLightOutput);
+
+ prefsHandler->write(EESIO_SYSTEM_TYPE, (uint8_t) configuration->systemType);
+ prefsHandler->write(EESIO_CAR_TYPE, (uint8_t) configuration->carType);
+ prefsHandler->write(EESIO_LOG_LEVEL, (uint8_t) configuration->logLevel);
+
+ prefsHandler->saveChecksum();
+}
diff --git a/SystemIO.h b/SystemIO.h
new file mode 100644
index 0000000..a5bcbb0
--- /dev/null
+++ b/SystemIO.h
@@ -0,0 +1,222 @@
+/*
+ * SystemIO.h
+ *
+ * Handles raw interaction with system I/O
+ *
+Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
+
+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 SYS_IO_H_
+#define SYS_IO_H_
+
+#include
+#include "config.h"
+#include "eeprom_layout.h"
+#include "PrefHandler.h"
+#include "Logger.h"
+#include "TickHandler.h"
+#include "Status.h"
+
+class Status;
+
+class SystemIOConfiguration
+{
+public:
+ enum SystemType {
+ GEVCU1 = 1,
+ GEVCU2 = 2,
+ GEVCU3 = 3,
+ GEVCU4 = 4
+ };
+
+ enum CarType {
+ OBD2 = 0x00,
+ Volvo_S80_Gas = 0x01,
+ Volvo_V50_Diesel = 0x02,
+ unkown = 0xff
+ };
+
+ uint8_t enableInput; // # of input for enable signal - required so that GEVCU enables the controller and requests torque/speed > 0
+ uint8_t chargePowerAvailableInput; // # of input to signal availability of charging power (shore power)
+ uint8_t interlockInput; // # of input to signal if the interlock circuit is closed and HV voltage can be applied
+ uint8_t reverseInput; // # of input to signal if reverse mode is selected
+ uint8_t absInput; // # of input to signal if ABS system is active
+ uint8_t gearChangeInput; // # of intput to signal that a gear change is in progress
+
+ uint16_t prechargeMillis; // milliseconds required for the pre-charge cycle
+ uint8_t prechargeRelayOutput; // # of output to use for the pre-charge relay or 255 if not used
+ uint8_t mainContactorOutput; // # of output to use for the main contactor relay (main contactor) or 255 if not used
+ uint8_t secondaryContactorOutput; // # of output to use for the secondary contactor relay or 255 if not used
+ uint8_t fastChargeContactorOutput; // # of output to use for the fast charge contactor relay or 255 if not used
+
+ uint8_t enableMotorOutput; // # of output to use for the enable signal/relay or 255 if not used
+ uint8_t enableChargerOutput; // # of output to activate the charger
+ uint8_t enableDcDcOutput; // # of output to enable the DC to DC cenverter
+ uint8_t enableHeaterOutput; // # of output to enable heater
+ uint8_t heaterTemperatureOn; // temperature in deg C below which the heater is turned on
+
+ uint8_t heaterValveOutput; // # of output to control heater valve (heat cabin or batteries)
+ uint8_t heaterPumpOutput; // # of output to control heater pump
+ uint8_t coolingPumpOutput; // # of output to control cooling pump
+ uint8_t coolingFanOutput; // # of output to use for the cooling fan relay or 255 if not used
+ uint8_t coolingTempOn; // temperature in degree celsius to start cooling
+ uint8_t coolingTempOff; // temperature in degree celsius to stop cooling
+
+ uint8_t brakeLightOutput; // #of output for brake light at regen or 255 if not used
+ uint8_t reverseLightOutput; // #of output for reverse light or 255 if not used
+ uint8_t powerSteeringOutput; // #of output for power steering or 255 if not used
+ uint8_t unusedOutput; // #of output for ... or 255 if not used
+
+ uint8_t warningOutput; // #of output for warning light/relay or 255 if not used
+ uint8_t powerLimitationOutput; // #of output for power limitation light or 255 if not used
+ uint8_t stateOfChargeOutput; // #of output to indicate the SoC or 255 if not used
+ uint8_t statusLightOutput; // #of output for the status light or 255 if not used
+
+ SystemType systemType; // the system type
+ CarType carType; // the type of car, so we know how to interpret which bytes
+ Logger::LogLevel logLevel; // the system's loglevel
+};
+
+class SystemIO : public TickObserver
+{
+public:
+ SystemIO();
+ virtual ~SystemIO();
+ void setup();
+ void handleTick();
+
+ void loadConfiguration();
+ void saveConfiguration();
+ SystemIOConfiguration *getConfiguration();
+
+ bool isEnableSignalPresent();
+ bool isChargePowerAvailable();
+ bool isInterlockPresent();
+ bool isReverseSignalPresent();
+ bool isABSActive();
+ bool isGearChangeActive();
+
+ void setEnableMotor(bool);
+ void setEnableCharger(bool);
+ void setEnableDcDc(bool);
+ void setEnableHeater(bool);
+
+ void setHeaterValve(bool);
+ void setHeaterPump(bool);
+ void setCoolingPump(bool);
+ void setCoolingFan(bool);
+
+ void setBrakeLight(bool);
+ void setReverseLight(bool);
+ void setPowerSteering(bool);
+ void setUnused(bool);
+
+ void setWarning(bool);
+ void setPowerLimitation(bool);
+ void setStateOfCharge(uint8_t);
+ void setStatusLight(uint8_t);
+
+ uint16_t getAnalogIn(uint8_t which);
+ void setDigitalOut(uint8_t which, boolean active);
+ bool getDigitalOut(uint8_t which);
+ void ADCPoll();
+ uint32_t getNextADCBuffer();
+ void printIOStatus();
+
+ void setSystemType(SystemIOConfiguration::SystemType);
+ SystemIOConfiguration::SystemType getSystemType();
+ void setCarType(SystemIOConfiguration::CarType);
+ SystemIOConfiguration::CarType getCarType();
+ void setLogLevel(Logger::LogLevel);
+ Logger::LogLevel getLogLevel();
+ void measurePreCharge();
+
+protected:
+
+private:
+ typedef struct {
+ uint16_t offset;
+ uint16_t gain;
+ } ADC_COMP;
+
+ uint8_t dig[CFG_NUMBER_DIGITAL_INPUTS];
+ uint8_t adc[CFG_NUMBER_ANALOG_INPUTS][2];
+ uint8_t out[CFG_NUMBER_DIGITAL_OUTPUTS];
+
+ volatile int bufn, obufn;
+ volatile uint16_t adcBuffer[CFG_NUMBER_ANALOG_INPUTS][256]; // 4 buffers of 256 readings
+ uint16_t adcValues[CFG_NUMBER_ANALOG_INPUTS * 2];
+ uint16_t adcOutValues[CFG_NUMBER_ANALOG_INPUTS];
+ ADC_COMP adcComp[CFG_NUMBER_ANALOG_INPUTS];
+
+ //the ADC values fluctuate a lot so smoothing is required.
+// int numberADCSamples;
+// uint16_t adcAverageBuffer[CFG_NUMBER_ANALOG_INPUTS][64];
+// uint8_t adcPointer[CFG_NUMBER_ANALOG_INPUTS]; //pointer to next position to use
+
+ bool useRawADC;
+ uint32_t preChargeStart; // time-stamp when pre-charge cycle has started
+ SystemIOConfiguration *configuration;
+ PrefHandler *prefsHandler;
+ bool deactivatedPowerSteering, deactivatedHeater;
+
+ void initializePinTables();
+ void initGevcu2PinTable();
+ void initGevcu3PinTable();
+ void initGevcu4PinTable();
+ void initGevcuLegacyPinTable();
+ void initializeDigitalIO();
+ void initializeAnalogIO();
+
+ uint16_t getDifferentialADC(uint8_t which);
+ uint16_t getRawADC(uint8_t which);
+ void setupFastADC();
+
+ void updateDigitalInputStatus();
+ void powerDownSystem();
+
+ bool handleState();
+ void handleCooling();
+ void handlePreCharge();
+ void handleCharging();
+ void handleBrakeLight();
+ void handleReverseLight();
+ void handleHighPowerDevices();
+
+ bool getDigitalIn(uint8_t which);
+ void setAnalogOut(uint8_t which, uint8_t value);
+
+ // for security reasons, these should stay private
+ void setPrechargeRelay(bool);
+ void setMainContactor(bool);
+ void setSecondaryContactor(bool);
+ void setFastChargeContactor(bool);
+
+ void logPreCharge();
+
+};
+
+extern SystemIO systemIO;
+
+#endif
diff --git a/ThinkBatteryManager.cpp b/ThinkBatteryManager.cpp
index 7af69cd..e976130 100644
--- a/ThinkBatteryManager.cpp
+++ b/ThinkBatteryManager.cpp
@@ -3,191 +3,210 @@
*
* Interface to the BMS which is within the Think City battery packs
*
-Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
-
-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.
+ Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
+
+ 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 "ThinkBatteryManager.h"
-ThinkBatteryManager::ThinkBatteryManager() : BatteryManager() {
- prefsHandler = new PrefHandler(THINKBMS);
- allowCharge = false;
- allowDischarge = false;
- commonName = "Think City BMS";
+ThinkBatteryManager::ThinkBatteryManager() :
+ BatteryManager()
+{
+ prefsHandler = new PrefHandler(THINKBMS);
+ commonName = "Th!nk City BMS";
}
-void ThinkBatteryManager::setup() {
- TickHandler::getInstance()->detach(this);
-
- Logger::info("add device: Th!nk City BMS (id: %X, %X)", THINKBMS, this);
+void ThinkBatteryManager::setup()
+{
+ BatteryManager::setup(); // run the parent class version of this function
- BatteryManager::setup(); // run the parent class version of this function
+ //Relevant BMS messages are 0x300 - 0x30F
+ canHandlerEv.attach(this, 0x300, 0x7f0, false);
+ ready = true;
- //Relevant BMS messages are 0x300 - 0x30F
- CanHandler::getInstanceEV()->attach(this, 0x300, 0x7f0, false);
+ tickHandler.attach(this, CFG_TICK_INTERVAL_BMS_THINK);
+}
- TickHandler::getInstance()->attach(this, CFG_TICK_INTERVAL_BMS_THINK);
+/**
+ * Tear down the device in a safe way.
+ */
+void ThinkBatteryManager::tearDown()
+{
+ BatteryManager::tearDown();
+ canHandlerEv.detach(this, 0x300, 0x7f0);
}
/*For all multibyte integers the format is MSB first, LSB last
-*/
-void ThinkBatteryManager::handleCanFrame(CAN_FRAME *frame) {
- int temp;
- switch (frame->id) {
- case 0x300: //Start up message
- //we're not really interested in much here except whether init worked.
- if ((frame->data.bytes[6] & 1) == 0) //there was an initialization error!
- {
- faultHandler.raiseFault(THINKBMS, FAULT_BMS_INIT, true);
- allowCharge = false;
- allowDischarge = false;
- }
- else
- {
- faultHandler.cancelOngoingFault(THINKBMS, FAULT_BMS_INIT);
- }
- break;
- case 0x301: //System Data 0
- //first two bytes = current, next two voltage, next two DOD, last two avg. temp
- //readings in tenths
- packVoltage = (frame->data.bytes[0] * 256 + frame->data.bytes[1]);
- packCurrent = (frame->data.bytes[2] * 256 + frame->data.bytes[3]);
- break;
- case 0x302: //System Data 1
- if ((frame->data.bytes[0] & 1) == 1) //Byte 0 bit 0 = general error
- {
- faultHandler.raiseFault(THINKBMS, FAULT_BMS_MISC, true);
- allowDischarge = false;
- allowCharge = false;
- }
- else
- {
- faultHandler.cancelOngoingFault(THINKBMS, FAULT_BMS_MISC);
- }
- if ((frame->data.bytes[2] & 1) == 1) //Byte 2 bit 0 = general isolation error
- {
- faultHandler.raiseFault(THINKBMS, FAULT_HV_BATT_ISOLATION, true);
- allowDischarge = false;
- allowCharge = false;
- }
- else
- {
- faultHandler.cancelOngoingFault(THINKBMS, FAULT_HV_BATT_ISOLATION);
- }
- //Min discharge voltage = bytes 4-5 - tenths of a volt
- //Max discharge current = bytes 6-7 - tenths of an amp
- temp = (S16)(frame->data.bytes[6] * 256 + frame->data.bytes[7]);
- if (temp > 0) allowDischarge = true;
- break;
- case 0x303: //System Data 2
- //bytes 0-1 = max charge voltage (tenths of volt)
- //bytes 2-3 = max charge current (tenths of amp)
- temp = (S16)(frame->data.bytes[2] * 256 + frame->data.bytes[3]);
- if (temp > 0) allowCharge = true;
- //byte 4 bit 1 = regen braking OK, bit 2 = Discharging OK
- //byte 6 bit 3 = EPO (emergency power off) happened, bit 5 = battery pack fan is on
- break;
- case 0x304: //System Data 3
- //Byte 2 lower 4 bits = highest error category
- //categories: 0 = no faults, 1 = Reserved, 2 = Warning, 3 = Delayed switch off, 4 = immediate switch off
- //bytes 4-5 = Pack max temperature (tenths of degree C) - Signed
- //byte 6-7 = Pack min temperature (tenths of a degree C) - Signed
- lowestCellTemp = (S16)(frame->data.bytes[4] * 256 + frame->data.bytes[5]);
- highestCellTemp = (S16)(frame->data.bytes[6] * 256 + frame->data.bytes[7]);
- break;
- case 0x305: //System Data 4
- //byte 2 bits 0-3 = BMS state
- //0 = idle state, 1 = discharge state (contactor closed), 15 = fault state
- //byte 2 bit 4 = Internal HV isolation fault
- //byte 2 bit 5 = External HV isolation fault
- break;
- case 0x306: //System Data 5
- //bytes 0-1 = Equiv. internal resistance in milliohms
- //not recommended to rely on so probably just ignore it
- break;
- //technically there is a specification for frames 0x307 - 0x30A but I have never seen these frames
- //sent on the canbus system so I doubt that they are used.
-/*
- case 0x307: //System Data 6
- case 0x308: //System Data 7
- case 0x309: //System Data 8
- case 0x30A: //System Data 9
- //do we care about the serial #? Probably not.
- case 0x30E: //Serial # part 1
- case 0x30B: //Serial # part 2
-*/
- }
+ */
+void ThinkBatteryManager::handleCanFrame(CAN_FRAME *frame)
+{
+ int temp;
+ switch (frame->id) {
+ case 0x300: //Start up message
+
+ //we're not really interested in much here except whether init worked.
+ if ((frame->data.bytes[6] & 1) == 0) { //there was an initialization error!
+ faultHandler.raiseFault(THINKBMS, FAULT_BMS_INIT, true);
+ allowCharge = false;
+ allowDischarge = false;
+ } else {
+ running = true;
+ faultHandler.cancelOngoingFault(THINKBMS, FAULT_BMS_INIT);
+ }
+
+ break;
+
+ case 0x301: //System Data 0
+ //first two bytes = current, next two voltage, next two DOD, last two avg. temp
+ //readings in tenths
+ packVoltage = (frame->data.bytes[0] * 256 + frame->data.bytes[1]);
+ packCurrent = (frame->data.bytes[2] * 256 + frame->data.bytes[3]);
+ break;
+
+ case 0x302: //System Data 1
+ if ((frame->data.bytes[0] & 1) == 1) { //Byte 0 bit 0 = general error
+ faultHandler.raiseFault(THINKBMS, FAULT_BMS_MISC, true);
+ allowDischarge = false;
+ allowCharge = false;
+ } else {
+ faultHandler.cancelOngoingFault(THINKBMS, FAULT_BMS_MISC);
+ }
+
+ if ((frame->data.bytes[2] & 1) == 1) { //Byte 2 bit 0 = general isolation error
+ faultHandler.raiseFault(THINKBMS, FAULT_HV_BATT_ISOLATION, true);
+ allowDischarge = false;
+ allowCharge = false;
+ } else {
+ faultHandler.cancelOngoingFault(THINKBMS, FAULT_HV_BATT_ISOLATION);
+ }
+ //Min discharge voltage = bytes 4-5 - tenths of a volt
+ //Max discharge current = bytes 6-7 - tenths of an amp
+ temp = (S16) (frame->data.bytes[6] * 256 + frame->data.bytes[7]);
+ if (temp > 0) {
+ allowDischarge = true;
+ }
+ break;
+
+ case 0x303:
+ //System Data 2
+ //bytes 0-1 = max charge voltage (tenths of volt)
+ //bytes 2-3 = max charge current (tenths of amp)
+ temp = (S16) (frame->data.bytes[2] * 256 + frame->data.bytes[3]);
+ if (temp > 0)
+ allowCharge = true;
+ //byte 4 bit 1 = regen braking OK, bit 2 = Discharging OK
+ //byte 6 bit 3 = EPO (emergency power off) happened, bit 5 = battery pack fan is on
+ break;
+
+ case 0x304:
+ //System Data 3
+ //Byte 2 lower 4 bits = highest error category
+ //categories: 0 = no faults, 1 = Reserved, 2 = Warning, 3 = Delayed switch off, 4 = immediate switch off
+ //bytes 4-5 = Pack max temperature (tenths of degree C) - Signed
+ //byte 6-7 = Pack min temperature (tenths of a degree C) - Signed
+ lowestCellTemp = (S16) (frame->data.bytes[4] * 256 + frame->data.bytes[5]);
+ highestCellTemp = (S16) (frame->data.bytes[6] * 256 + frame->data.bytes[7]);
+ break;
+
+ case 0x305:
+ //System Data 4
+ //byte 2 bits 0-3 = BMS state
+ //0 = idle state, 1 = discharge state (contactor closed), 15 = fault state
+ //byte 2 bit 4 = Internal HV isolation fault
+ //byte 2 bit 5 = External HV isolation fault
+ break;
+
+ case 0x306:
+ //System Data 5
+ //bytes 0-1 = Equiv. internal resistance in milliohms
+ //not recommended to rely on so probably just ignore it
+ break;
+ //technically there is a specification for frames 0x307 - 0x30A but I have never seen these frames
+ //sent on the canbus system so I doubt that they are used.
+ /*
+ case 0x307: //System Data 6
+ case 0x308: //System Data 7
+ case 0x309: //System Data 8
+ case 0x30A: //System Data 9
+ //do we care about the serial #? Probably not.
+ case 0x30E: //Serial # part 1
+ case 0x30B: //Serial # part 2
+ */
+ }
}
-void ThinkBatteryManager::handleTick() {
- BatteryManager::handleTick(); //kick the ball up to papa
+void ThinkBatteryManager::handleTick()
+{
+ BatteryManager::handleTick(); //kick the ball up to papa
- sendKeepAlive();
-
+ sendKeepAlive();
}
-//Contactors in pack will close if we sent these two frames with all zeros.
-void ThinkBatteryManager::sendKeepAlive()
+//Contactors in pack will close if we sent these two frames with all zeros.
+void ThinkBatteryManager::sendKeepAlive()
{
- CAN_FRAME output;
- output.length = 3;
- output.id = 0x310;
- output.extended = 0; //standard frame
- output.rtr = 0;
- for (int i = 0; i < 8; i++) output.data.bytes[i] = 0;
- CanHandler::getInstanceEV()->sendFrame(output);
-
- output.id = 0x311;
- output.length = 2;
- CanHandler::getInstanceEV()->sendFrame(output);
+ CAN_FRAME output;
+ output.length = 3;
+ output.id = 0x310;
+ output.extended = 0; //standard frame
+ output.rtr = 0;
+
+ for (int i = 0; i < 8; i++) {
+ output.data.bytes[i] = 0;
+ }
+
+ canHandlerEv.sendFrame(output);
+
+ output.id = 0x311;
+ output.length = 2;
+ canHandlerEv.sendFrame(output);
}
-DeviceId ThinkBatteryManager::getId()
+DeviceId ThinkBatteryManager::getId()
{
- return (THINKBMS);
+ return (THINKBMS);
}
-bool ThinkBatteryManager::hasPackVoltage()
+bool ThinkBatteryManager::hasPackVoltage()
{
- return true;
+ return true;
}
-bool ThinkBatteryManager::hasPackCurrent()
+bool ThinkBatteryManager::hasPackCurrent()
{
- return true;
+ return true;
}
-bool ThinkBatteryManager::hasTemperatures()
+bool ThinkBatteryManager::hasCellTemperatures()
{
- return true;
+ return true;
}
-bool ThinkBatteryManager::isChargeOK()
+bool ThinkBatteryManager::hasAllowCharging()
{
- return allowCharge;
+ return true;
}
-bool ThinkBatteryManager::isDischargeOK()
+bool ThinkBatteryManager::hasAllowDischarging()
{
- return allowDischarge;
+ return true;
}
-
diff --git a/ThinkBatteryManager.h b/ThinkBatteryManager.h
index 887e81d..41080d3 100644
--- a/ThinkBatteryManager.h
+++ b/ThinkBatteryManager.h
@@ -24,8 +24,8 @@ 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 THINKBATT_H_
#define THINKBATT_H_
@@ -35,23 +35,25 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
#include "DeviceManager.h"
#include "BatteryManager.h"
#include "CanHandler.h"
+#include "FaultHandler.h"
class ThinkBatteryManager : public BatteryManager, CanObserver
{
public:
- ThinkBatteryManager();
- void setup();
- void handleTick();
- void handleCanFrame(CAN_FRAME *frame);
- DeviceId getId();
- bool hasPackVoltage();
- bool hasPackCurrent();
- bool hasTemperatures();
- bool isChargeOK();
- bool isDischargeOK();
+ ThinkBatteryManager();
+ void setup();
+ void tearDown();
+ void handleTick();
+ void handleCanFrame(CAN_FRAME *frame);
+ DeviceId getId();
+ bool hasPackVoltage();
+ bool hasPackCurrent();
+ bool hasCellTemperatures();
+ bool hasAllowCharging();
+ bool hasAllowDischarging();
protected:
private:
- void sendKeepAlive();
+ void sendKeepAlive();
};
#endif
diff --git a/Throttle.cpp b/Throttle.cpp
index 96b5c7a..747662e 100644
--- a/Throttle.cpp
+++ b/Throttle.cpp
@@ -30,9 +30,19 @@
/*
* Constructor
*/
-Throttle::Throttle() : Device() {
- level = 0;
- status = OK;
+Throttle::Throttle() : Device()
+{
+ level = 0;
+ throttleStatus = OK;
+}
+
+/**
+ * Tear down the controller in a safe way.
+ */
+void Throttle::tearDown()
+{
+ Device::tearDown();
+ level = 0;
}
/*
@@ -41,15 +51,23 @@ Throttle::Throttle() : Device() {
*
* Get's called by the sub-class which is triggered by the tick handler
*/
-void Throttle::handleTick() {
- Device::handleTick();
-
- RawSignalData *rawSignals = acquireRawSignal(); // get raw data from the throttle device
- if (validateSignal(rawSignals)) { // validate the raw data
- uint16_t position = calculatePedalPosition(rawSignals); // bring the raw data into a range of 0-1000 (without mapping)
- level = mapPedalPosition(position); // apply mapping of the 0-1000 range to the user defined settings
- } else
- level = 0;
+void Throttle::handleTick()
+{
+ Device::handleTick();
+
+ RawSignalData *rawSignals = acquireRawSignal(); // get raw data from the throttle device
+
+ if (validateSignal(rawSignals)) { // validate the raw data
+ uint16_t position = calculatePedalPosition(rawSignals); // bring the raw data into a range of 0-1000 (without mapping)
+ level = mapPedalPosition(position); // apply mapping of the 0-1000 range to the user defined settings
+ running = true;
+ } else {
+ level = 0;
+ running = false;
+ }
+ if(logger.isDebug()) {
+ logger.debug(this, "raw: %d, level: %d, running: %d", rawSignals->input1, level, running);
+ }
}
/*
@@ -79,155 +97,178 @@ void Throttle::handleTick() {
* Important pre-condition (to be checked when changing parameters) :
* 0 <= positionRegenMaximum <= positionRegenMinimum <= positionForwardMotionStart <= positionHalfPower
*/
-int16_t Throttle::mapPedalPosition(int16_t pedalPosition) {
- int16_t throttleLevel, range, value;
- ThrottleConfiguration *config = (ThrottleConfiguration *) getConfiguration();
-
- throttleLevel = 0;
-
- if (pedalPosition == 0 && config->creep > 0) {
- throttleLevel = 10 * config->creep;
- } else if (pedalPosition <= config->positionRegenMinimum) {
- if (pedalPosition >= config->positionRegenMaximum) {
- range = config->positionRegenMinimum - config->positionRegenMaximum;
- value = pedalPosition - config->positionRegenMaximum;
- if (range != 0) // prevent div by zero, should result in 0 throttle if min==max
- throttleLevel = -10 * config->minimumRegen + (config->maximumRegen - config->minimumRegen) * (100 - value * 100 / range) / -10;
- } else {
- // no ramping yet below positionRegenMaximum, just drop to 0
-// range = config->positionRegenMaximum;
-// value = pedalPosition;
-// throttleLevel = -10 * config->maximumRegen * value / range;
- }
- }
-
- if (pedalPosition >= config->positionForwardMotionStart) {
- if (pedalPosition <= config->positionHalfPower) {
- range = config->positionHalfPower - config->positionForwardMotionStart;
- value = pedalPosition - config->positionForwardMotionStart;
- if (range != 0) // prevent div by zero, should result in 0 throttle if half==startFwd
- throttleLevel = 500 * value / range;
- } else {
- range = 1000 - config->positionHalfPower;
- value = pedalPosition - config->positionHalfPower;
- throttleLevel = 500 + 500 * value / range;
- }
- }
- //Logger::debug("throttle level: %d", throttleLevel);
-
- //A bit of a kludge. Normally it isn't really possible to ever get to
- //100% output. This next line just fudges the numbers a bit to make it
- //more likely to get that last bit of power
- if (throttleLevel > 979) throttleLevel = 1000;
-
- return throttleLevel;
+int16_t Throttle::mapPedalPosition(int16_t pedalPosition)
+{
+ int16_t throttleLevel, range, value;
+ ThrottleConfiguration *config = (ThrottleConfiguration *) getConfiguration();
+
+ throttleLevel = 0;
+
+ if (pedalPosition <= config->positionRegenMinimum) {
+ if (pedalPosition >= config->positionRegenMaximum) {
+ range = config->positionRegenMinimum - config->positionRegenMaximum;
+ value = pedalPosition - config->positionRegenMaximum;
+
+ if (range != 0) { // prevent div by zero, should result in 0 throttle if min==max
+ throttleLevel = -10 * config->minimumRegen + (config->maximumRegen - config->minimumRegen) * (100 - value * 100 / range) / -10;
+ }
+ } else {
+ range = config->positionRegenMaximum;
+ value = pedalPosition;
+ throttleLevel = -10 * config->maximumRegen * value / range;
+ }
+ }
+
+ if (pedalPosition >= config->positionForwardMotionStart) {
+ if (pedalPosition <= config->positionHalfPower) {
+ range = config->positionHalfPower - config->positionForwardMotionStart;
+ value = pedalPosition - config->positionForwardMotionStart;
+
+ if (range != 0) { // prevent div by zero, should result in 0 throttle if half==startFwd
+ throttleLevel = 500 * value / range;
+ }
+ } else {
+ range = 1000 - config->positionHalfPower;
+ value = pedalPosition - config->positionHalfPower;
+ throttleLevel = 500 + 500 * value / range;
+ }
+ }
+
+ //logger.debug("throttle level: %d", throttleLevel);
+
+ //A bit of a kludge. Normally it isn't really possible to ever get to
+ //100% output. This next line just fudges the numbers a bit to make it
+ //more likely to get that last bit of power
+ if (throttleLevel > 979) {
+ throttleLevel = 1000;
+ }
+
+ return throttleLevel;
}
+
/*
* Make sure input level stays within margins (min/max) then map the constrained
* level linearly to a value from 0 to 1000.
*/
-uint16_t Throttle::normalizeAndConstrainInput(int32_t input, int32_t min, int32_t max) {
- return constrain(normalizeInput(input, min, max), (int32_t) 0, (int32_t) 1000);
+uint16_t Throttle::normalizeAndConstrainInput(int32_t input, int32_t min, int32_t max)
+{
+ return constrain(normalizeInput(input, min, max), (int32_t) 0, (int32_t) 1000);
}
/*
* Map the constrained level linearly to a signed value from 0 to 1000.
*/
-int32_t Throttle::normalizeInput(int32_t input, int32_t min, int32_t max) {
- return map(input, min, max, (int32_t) 0, (int32_t) 1000);
+int32_t Throttle::normalizeInput(int32_t input, int32_t min, int32_t max)
+{
+ return map(input, min, max, (int32_t) 0, (int32_t) 1000);
}
/*
* Returns the currently calculated/mapped throttle level (from -1000 to 1000).
*/
-int16_t Throttle::getLevel() {
- return level;
+int16_t Throttle::getLevel()
+{
+ return level;
}
/*
* Return the throttle's current status
*/
-Throttle::ThrottleStatus Throttle::getStatus() {
- return status;
+Throttle::ThrottleStatus Throttle::getStatus()
+{
+ return throttleStatus;
}
/*
* Is the throttle faulted?
*/
-bool Throttle::isFaulted() {
- return status != OK;
+bool Throttle::isFaulted()
+{
+ return throttleStatus != OK;
}
/*
* Return the device type
*/
-DeviceType Throttle::getType() {
- return DEVICE_THROTTLE;
+DeviceType Throttle::getType()
+{
+ return DEVICE_THROTTLE;
}
-RawSignalData* Throttle::acquireRawSignal() {
- return NULL;
+RawSignalData* Throttle::acquireRawSignal()
+{
+ return NULL;
}
-bool Throttle::validateSignal(RawSignalData*) {
- return false;
+bool Throttle::validateSignal(RawSignalData*)
+{
+ return false;
}
-uint16_t Throttle::calculatePedalPosition(RawSignalData*) {
- return 0;
+uint16_t Throttle::calculatePedalPosition(RawSignalData*)
+{
+ return 0;
}
/*
* Load the config parameters which are required by all throttles
*/
-void Throttle::loadConfiguration() {
- ThrottleConfiguration *config = (ThrottleConfiguration *) getConfiguration();
+void Throttle::loadConfiguration()
+{
+ ThrottleConfiguration *config = (ThrottleConfiguration *) getConfiguration();
- Device::loadConfiguration(); // call parent
+ Device::loadConfiguration(); // call parent
+ logger.info(this, "Throttle configuration:");
#ifdef USE_HARD_CODED
- if (false) {
+
+ if (false) {
#else
- if (prefsHandler->checksumValid()) { //checksum is good, read in the values stored in EEPROM
+
+ if (prefsHandler->checksumValid()) { //checksum is good, read in the values stored in EEPROM
#endif
- prefsHandler->read(EETH_REGEN_MIN, &config->positionRegenMinimum);
- prefsHandler->read(EETH_REGEN_MAX, &config->positionRegenMaximum);
- prefsHandler->read(EETH_FWD, &config->positionForwardMotionStart);
- prefsHandler->read(EETH_MAP, &config->positionHalfPower);
- prefsHandler->read(EETH_CREEP, &config->creep);
- prefsHandler->read(EETH_MIN_ACCEL_REGEN, &config->minimumRegen);
- prefsHandler->read(EETH_MAX_ACCEL_REGEN, &config->maximumRegen);
- } else { //checksum invalid. Reinitialize values, leave storing them to the subclasses
- config->positionRegenMinimum = ThrottleRegenMinValue;
- config->positionRegenMaximum = ThrottleRegenMaxValue;
- config->positionForwardMotionStart = ThrottleFwdValue;
- config->positionHalfPower = ThrottleMapValue;
- config->creep = ThrottleCreepValue;
- config->minimumRegen = ThrottleMinRegenValue; //percentage of minimal power to use when regen starts
- config->maximumRegen = ThrottleMaxRegenValue; //percentage of full power to use for regen at throttle
- }
- Logger::debug(THROTTLE, "RegenMax: %l RegenMin: %l Fwd: %l Map: %l", config->positionRegenMaximum, config->positionRegenMinimum,
- config->positionForwardMotionStart, config->positionHalfPower);
- Logger::debug(THROTTLE, "MinRegen: %d MaxRegen: %d", config->minimumRegen, config->maximumRegen);
+ prefsHandler->read(EETH_LEVEL_MIN, &config->minimumLevel);
+ prefsHandler->read(EETH_LEVEL_MAX, &config->maximumLevel);
+ prefsHandler->read(EETH_REGEN_MIN, &config->positionRegenMinimum);
+ prefsHandler->read(EETH_REGEN_MAX, &config->positionRegenMaximum);
+ prefsHandler->read(EETH_FWD, &config->positionForwardMotionStart);
+ prefsHandler->read(EETH_MAP, &config->positionHalfPower);
+ prefsHandler->read(EETH_MIN_ACCEL_REGEN, &config->minimumRegen);
+ prefsHandler->read(EETH_MAX_ACCEL_REGEN, &config->maximumRegen);
+ } else { //checksum invalid. Reinitialize values, leave storing them to the subclasses
+ config->minimumLevel = 95;
+ config->maximumLevel = 3150;
+ config->positionRegenMinimum = 270;
+ config->positionRegenMaximum = 30;
+ config->positionForwardMotionStart = 300;
+ config->positionHalfPower = 750;
+ config->minimumRegen = 0;
+ config->maximumRegen = 50;
+ }
+
+ logger.info(this, "RegenMax: %ld RegenMin: %ld Fwd: %ld Map: %ld", config->positionRegenMaximum, config->positionRegenMinimum,
+ config->positionForwardMotionStart, config->positionHalfPower);
+ logger.info(this, "MinRegen: %d MaxRegen: %d", config->minimumRegen, config->maximumRegen);
+ logger.info(this, "T1 MIN: %ld, T1 MAX: %ld", config->minimumLevel, config->maximumLevel);
}
/*
* Store the current configuration to EEPROM
*/
-void Throttle::saveConfiguration() {
- ThrottleConfiguration *config = (ThrottleConfiguration *) getConfiguration();
-
- Device::saveConfiguration(); // call parent
+void Throttle::saveConfiguration()
+{
+ ThrottleConfiguration *config = (ThrottleConfiguration *) getConfiguration();
- prefsHandler->write(EETH_REGEN_MIN, config->positionRegenMinimum);
- prefsHandler->write(EETH_REGEN_MAX, config->positionRegenMaximum);
- prefsHandler->write(EETH_FWD, config->positionForwardMotionStart);
- prefsHandler->write(EETH_MAP, config->positionHalfPower);
- prefsHandler->write(EETH_CREEP, config->creep);
- prefsHandler->write(EETH_MIN_ACCEL_REGEN, config->minimumRegen);
- prefsHandler->write(EETH_MAX_ACCEL_REGEN, config->maximumRegen);
- prefsHandler->saveChecksum();
+ Device::saveConfiguration(); // call parent
- Logger::console("Throttle configuration saved");
+ prefsHandler->write(EETH_LEVEL_MIN, config->minimumLevel);
+ prefsHandler->write(EETH_LEVEL_MAX, config->maximumLevel);
+ prefsHandler->write(EETH_REGEN_MIN, config->positionRegenMinimum);
+ prefsHandler->write(EETH_REGEN_MAX, config->positionRegenMaximum);
+ prefsHandler->write(EETH_FWD, config->positionForwardMotionStart);
+ prefsHandler->write(EETH_MAP, config->positionHalfPower);
+ prefsHandler->write(EETH_MIN_ACCEL_REGEN, config->minimumRegen);
+ prefsHandler->write(EETH_MAX_ACCEL_REGEN, config->maximumRegen);
+ prefsHandler->saveChecksum();
}
diff --git a/Throttle.h b/Throttle.h
index 604d45e..c9fa659 100644
--- a/Throttle.h
+++ b/Throttle.h
@@ -41,60 +41,66 @@
* E.g. for a three pot pedal, all signals could be used.
*/
struct RawSignalData {
- int32_t input1; // e.g. pot #1 or the signal from a can bus throttle
- int32_t input2; // e.g. pot #2 (optional)
- int32_t input3; // e.g. pot #3 (optional)
+ int32_t input1; // e.g. pot #1 or the signal from a can bus throttle
+ int32_t input2; // e.g. pot #2 (optional)
+ int32_t input3; // e.g. pot #3 (optional)
};
/*
* A abstract class to hold throttle configuration parameters.
* Can be extended by the subclass.
*/
-class ThrottleConfiguration: public DeviceConfiguration {
+class ThrottleConfiguration: public DeviceConfiguration
+{
public:
- uint16_t positionRegenMaximum, positionRegenMinimum; // throttle position where regen is highest and lowest
- uint16_t positionForwardMotionStart, positionHalfPower; // throttle position where forward motion starts and the mid point of throttle
- uint8_t maximumRegen; // percentage of max torque allowable for regen at maximum level
- uint8_t minimumRegen; // percentage of max torque allowable for regen at minimum level
- uint8_t creep; // percentage of torque used for creep function (imitate creep of automatic transmission, set 0 to disable)
+ uint16_t minimumLevel, maximumLevel; // values for when the pedal is at its min and max
+ uint16_t positionRegenMaximum, positionRegenMinimum; // throttle position where regen is highest and lowest
+ uint16_t positionForwardMotionStart, positionHalfPower; // throttle position where forward motion starts and the mid point of throttle
+ uint8_t maximumRegen; // percentage of max torque allowable for regen at maximum level
+ uint8_t minimumRegen; // percentage of max torque allowable for regen at minimum level
};
/*
* Abstract class for all throttle implementations.
*/
-class Throttle: public Device {
+class Throttle: public Device
+{
public:
- enum ThrottleStatus {
- OK,
- ERR_LOW_T1,
- ERR_LOW_T2,
- ERR_HIGH_T1,
- ERR_HIGH_T2,
- ERR_MISMATCH,
- ERR_MISC
- };
-
- Throttle();
- virtual int16_t getLevel();
- void handleTick();
- virtual ThrottleStatus getStatus();
- virtual bool isFaulted();
- virtual DeviceType getType();
-
- virtual RawSignalData *acquireRawSignal();
- void loadConfiguration();
- void saveConfiguration();
+ enum ThrottleStatus {
+ OK,
+ ERR_LOW_T1,
+ ERR_LOW_T2,
+ ERR_HIGH_T1,
+ ERR_HIGH_T2,
+ ERR_MISMATCH,
+ ERR_MISC
+ };
+
+ Throttle();
+ void tearDown();
+ virtual int16_t getLevel();
+ void handleTick();
+ virtual ThrottleStatus getStatus();
+ virtual bool isFaulted();
+ virtual DeviceType getType();
+
+ virtual RawSignalData *acquireRawSignal();
+ void loadConfiguration();
+ void saveConfiguration();
protected:
- ThrottleStatus status;
- virtual bool validateSignal(RawSignalData *);
- virtual uint16_t calculatePedalPosition(RawSignalData *);
- virtual int16_t mapPedalPosition(int16_t);
- uint16_t normalizeAndConstrainInput(int32_t, int32_t, int32_t);
- int32_t normalizeInput(int32_t, int32_t, int32_t);
+ ThrottleStatus throttleStatus;
+ virtual bool validateSignal(RawSignalData *);
+ virtual uint16_t calculatePedalPosition(RawSignalData *);
+ virtual int16_t mapPedalPosition(int16_t);
+ uint16_t normalizeAndConstrainInput(int32_t, int32_t, int32_t);
+ int32_t normalizeInput(int32_t, int32_t, int32_t);
+
+ const String VALUE_OUT_OF_RANGE = "value out of range: %ld";
+ const String NORMAL_OPERATION = "normal operation restored";
private:
- int16_t level; // the final signed throttle level. [-1000, 1000] in permille of maximum
+ int16_t level; // the final signed throttle level. [-1000, 1000] in permille of maximum
};
#endif
diff --git a/ThrottleDetector.cpp b/ThrottleDetector.cpp
index 29074e4..8d1e479 100644
--- a/ThrottleDetector.cpp
+++ b/ThrottleDetector.cpp
@@ -33,321 +33,341 @@
/*
* The constructor takes a pointer to a throttle
*/
-ThrottleDetector::ThrottleDetector(Throttle *throttle) {
- this->throttle = throttle;
- config = (PotThrottleConfiguration *) throttle->getConfiguration();
- state = DoNothing;
- maxThrottleReadingDeviationPercent = 100; // 10% in 0-1000 scale
- Logger::debug("ThrottleDetector constructed with throttle %d", throttle);
- resetValues();
+ThrottleDetector::ThrottleDetector(Throttle *throttle)
+{
+ this->throttle = throttle;
+ config = (PotThrottleConfiguration *) throttle->getConfiguration();
+ state = DoNothing;
+ maxThrottleReadingDeviationPercent = 100; // 10% in 0-1000 scale
+ logger.debug("ThrottleDetector constructed with throttle %d", throttle);
+ resetValues();
}
/*
* Nothing to do in the destructor right now but good to have as a general rule
*/
-ThrottleDetector::~ThrottleDetector() {
+ThrottleDetector::~ThrottleDetector()
+{
}
/*
* Operations run asynchronously in small increments each time this
* method is called so we track the state and resume the operation each call
*/
-void ThrottleDetector::handleTick() {
- switch (state) {
- case DetectMinWait:
- detectMinWait();
- break;
- case DetectMinCalibrate:
- detectMinCalibrate();
- break;
- case DetectMaxWait:
- detectMaxWait();
- break;
- case DetectMaxCalibrate:
- detectMaxCalibrate();
- break;
-
- case DoNothing:
- break;
- }
+void ThrottleDetector::handleTick()
+{
+ switch (state) {
+ case DetectMinWait:
+ detectMinWait();
+ break;
+
+ case DetectMinCalibrate:
+ detectMinCalibrate();
+ break;
+
+ case DetectMaxWait:
+ detectMaxWait();
+ break;
+
+ case DetectMaxCalibrate:
+ detectMaxCalibrate();
+ break;
+
+ case DoNothing:
+ break;
+ }
}
/*
* Run the complete throttle detection.
* Step 1. Kick it off
*/
-void ThrottleDetector::detect() {
- Logger::console("Throttle detection starting. Do NOT press the pedal until instructed.");
-
- resetValues();
-
- // reset stats
- sampleCount = 0;
- linearCount = 0;
- inverseCount = 0;
- for (int i = 0; i < 200; i++) {
- throttle1Values[i] = 0;
- throttle2Values[i] = 0;
- }
+void ThrottleDetector::detect()
+{
+ logger.console("Throttle detection starting. Do NOT press the pedal until instructed.");
+
+ resetValues();
+
+ // reset stats
+ sampleCount = 0;
+ linearCount = 0;
+ inverseCount = 0;
+
+ for (int i = 0; i < 200; i++) {
+ throttle1Values[i] = 0;
+ throttle2Values[i] = 0;
+ }
- // we wait for 2 seconds so kick this off
- startTime = millis();
- state = DetectMinWait;
+ // we wait for 2 seconds so kick this off
+ startTime = millis();
+ state = DetectMinWait;
- TickHandler::getInstance()->attach(this, CFG_TICK_INTERVAL_POT_THROTTLE);
+ tickHandler.attach(this, CFG_TICK_INTERVAL_POT_THROTTLE);
}
/*
* Step 2. Wait for 2 seconds then start taking MIN readings
*/
-void ThrottleDetector::detectMinWait() {
- if ((millis() - startTime) >= 2000) {
- // take MIN readings for 2 seconds
- startTime = millis();
- readThrottleValues();
- state = DetectMinCalibrate;
- }
+void ThrottleDetector::detectMinWait()
+{
+ if ((millis() - startTime) >= 2000) {
+ // take MIN readings for 2 seconds
+ startTime = millis();
+ readThrottleValues();
+ state = DetectMinCalibrate;
+ }
}
/*
* Step 3. Take MIN readings for 2 seconds then start waiting again
*/
-void ThrottleDetector::detectMinCalibrate() {
- if ((millis() - startTime) < 2000 || sampleCount < maxSamples / 3) {
- readThrottleValues();
- } else {
- displayCalibratedValues(true);
-
- // save rest minimums
- throttle1MinRest = throttle1Min;
- throttle1MaxRest = throttle1Max;
- throttle2MinRest = throttle2Min;
- throttle2MaxRest = throttle2Max;
-
- Logger::console("\nSmoothly depress the pedal to full acceleration");
- Logger::console("and hold the pedal until complete");
-
- // wait for 5 seconds so they can react and then still get some readings
- startTime = millis();
- state = DetectMaxWait;
- }
+void ThrottleDetector::detectMinCalibrate()
+{
+ if ((millis() - startTime) < 2000 || sampleCount < maxSamples / 3) {
+ readThrottleValues();
+ } else {
+ displayCalibratedValues(true);
+
+ // save rest minimums
+ throttle1MinRest = throttle1Min;
+ throttle1MaxRest = throttle1Max;
+ throttle2MinRest = throttle2Min;
+ throttle2MaxRest = throttle2Max;
+
+ logger.console("\nSmoothly depress the pedal to full acceleration");
+ logger.console("and hold the pedal until complete");
+
+ // wait for 5 seconds so they can react and then still get some readings
+ startTime = millis();
+ state = DetectMaxWait;
+ }
}
/*
* Step 4. Wait for 5 seconds then start taking MAX readings
*/
-void ThrottleDetector::detectMaxWait() {
- if ((millis() - startTime) >= 5000 || sampleCount >= maxSamples * 2 / 3) {
-
- // take MAX readings for 2 seconds
- resetValues();
- startTime = millis();
- readThrottleValues();
- state = DetectMaxCalibrate;
- } else {
- readThrottleValues();
- }
+void ThrottleDetector::detectMaxWait()
+{
+ if ((millis() - startTime) >= 5000 || sampleCount >= maxSamples * 2 / 3) {
+
+ // take MAX readings for 2 seconds
+ resetValues();
+ startTime = millis();
+ readThrottleValues();
+ state = DetectMaxCalibrate;
+ } else {
+ readThrottleValues();
+ }
}
/*
* Step 5. Take MAX readings for 3 seconds then show results
*/
-void ThrottleDetector::detectMaxCalibrate() {
- if ((millis() - startTime) < 2000 && sampleCount < maxSamples) {
- readThrottleValues();
- } else {
- displayCalibratedValues(false);
-
- // take some stats before normalizing min/max
- int throttle1MinFluctuation = abs(throttle1MaxRest-throttle1MinRest);
- int throttle2MinFluctuation = abs(throttle2MaxRest-throttle2MinRest);
- int throttle1MaxFluctuation = abs(throttle1Max-throttle1Min);
- int throttle2MaxFluctuation = abs(throttle2Max-throttle2Min);
-
- // Determine throttle type based off min/max
- if (throttle1MinRest > throttle1Min+maxThrottleReadingDeviationPercent) { // high to low pot
- throttle1HighLow = true;
- }
-
- if (throttle2MinRest > throttle2Min+maxThrottleReadingDeviationPercent) { // high to low pot
- throttle2HighLow = true;
- }
-
- // restore the true min
- throttle1Min = throttle1MinRest;
-
- if ((throttle1HighLow && !throttle2HighLow) || (throttle2HighLow && !throttle1HighLow)) {
- throttle2Inverse = true;
- }
-
- // Detect grounded pin (always zero) or floating values which indicate no potentiometer provided
- if ((throttle2MinRest == 0 && throttle2MaxRest == 0 && throttle2Min == INT16_MAX && throttle2Max == 0)
- || (abs(throttle2MaxRest-throttle2Max) < maxThrottleReadingDeviationPercent
- && abs(throttle2MinRest-throttle2Min) < maxThrottleReadingDeviationPercent)) {
- potentiometerCount = 1;
- } else {
- potentiometerCount = 2;
- }
-
- // restore the true min/max for T2
- if ( throttle2Inverse ) {
- throttle2Max = throttle2MaxRest;
- } else {
- throttle2Min = throttle2MinRest;
- }
-
- Logger::debug("Inverse: %s, throttle2Min: %d, throttle2Max: %d", (throttle2Inverse?"true":"false"), throttle2Min, throttle2Max);
-
- // fluctuation percentages - make sure not to divide by zero
- if (!(throttle1Max == throttle1Min))
- {
- throttle1MinFluctuationPercent = throttle1MinFluctuation * 100 / abs(throttle1Max - throttle1Min);
- throttle1MaxFluctuationPercent = throttle1MaxFluctuation * 100 / abs(throttle1Max - throttle1Min);
- }
- else
- {
- throttle1MinFluctuationPercent = 0;
- throttle1MaxFluctuationPercent = 0;
- }
- if (!(throttle2Max == throttle2Min))
- {
- throttle2MinFluctuationPercent = throttle2MinFluctuation * 100 / abs(throttle2Max - throttle2Min);
- throttle2MaxFluctuationPercent = throttle2MaxFluctuation * 100 / abs(throttle2Max - throttle2Min);
- }
- else
- {
- throttle2MinFluctuationPercent = 0;
- throttle2MaxFluctuationPercent = 0;
- }
-
- // Determine throttle subtype by examining the data sampled
- for (int i = 0; i < sampleCount; i++) {
- // normalize the values to a 0-1000 scale using the found min/max
- uint16_t value1 = normalize(throttle1Values[i], throttle1Min, throttle1Max, 0, 1000);
- uint16_t value2 = normalize(throttle2Values[i], throttle2Min, throttle2Max, 0, 1000);
-
- // see if they match known subtypes
- linearCount += checkLinear(value1, value2);
- inverseCount += checkInverse(value1, value2);
-
- //Logger::debug("T1: %d, T2: %d = NT1: %d, NT2: %d, L: %d, I: %d", throttle1Values[i], throttle2Values[i], value1, value2, linearCount, inverseCount);
- }
-
- throttleSubType = 0;
- if (potentiometerCount > 1) {
- // For dual pots, we trust the detection of >75%
- if ((linearCount * 100) / sampleCount > 75) {
- throttleSubType = 1;
- } else if ((inverseCount * 100) / sampleCount > 75) {
- throttleSubType = 2;
- }
- } else {
- // For single pots we use the high/low
- if (throttle1HighLow) {
- throttleSubType = 2;
- } else {
- throttleSubType = 1;
- }
- }
-
- char *type = "UNKNOWN";
- if (throttleSubType == 1) {
- type = "Linear";
- } else if (throttleSubType == 2) {
- type = "Inverse";
- }
-
- if ( Logger::isDebug()) {
- Logger::console("\n----- RAW values ----");
- for (int i = 0; i < sampleCount; i++) {
- Logger::console("T1: %d, T2: %d", throttle1Values[i], throttle2Values[i]);
- }
- }
-
- Logger::console("\n=======================================");
- Logger::console("Detection complete");
- Logger::console("Num samples taken: %d", sampleCount);
- Logger::console("Num potentiometers found: %d", potentiometerCount);
- Logger::console("T1: %d to %d %s", (throttle1HighLow ? throttle1Max : throttle1Min), (throttle1HighLow ? throttle1Min : throttle1Max),
- (throttle1HighLow ? "HIGH-LOW" : "LOW-HIGH"));
- Logger::console("T1: rest fluctuation %d%%, full throttle fluctuation %d%%", throttle1MinFluctuationPercent, throttle1MaxFluctuationPercent);
-
- if (potentiometerCount > 1) {
- Logger::console("T2: %d to %d %s %s", (throttle2HighLow ? throttle2Max : throttle2Min), (throttle2HighLow ? throttle2Min : throttle2Max),
- (throttle2HighLow ? "HIGH-LOW" : "LOW-HIGH"), (throttle2Inverse ? " (Inverse of T1)" : ""));
- Logger::console("T2: rest fluctuation %d%%, full throttle fluctuation %d%%", throttle2MinFluctuationPercent, throttle2MaxFluctuationPercent);
- Logger::console("Num linear throttle matches: %d", linearCount);
- Logger::console("Num inverse throttle matches: %d", inverseCount);
- }
-
- Logger::console("Throttle type: %s", type);
- Logger::console("========================================");
-
- // update the throttle's configuration (without storing it yet)
- config->minimumLevel1 = throttle1Min;
- config->maximumLevel1 = throttle1Max;
- config->numberPotMeters = potentiometerCount;
- if (config->numberPotMeters > 1) {
- config->minimumLevel2 = throttle2Min;
- config->maximumLevel2 = throttle2Max;
- } else {
- config->minimumLevel2 = 0;
- config->maximumLevel2 = 0;
- }
- config->throttleSubType = throttleSubType;
-
- // Done!
- state = DoNothing;
- TickHandler::getInstance()->detach(this);
-
- // send updates to ichip wifi
- DeviceManager::getInstance()->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_CONFIG_CHANGE, NULL);
+void ThrottleDetector::detectMaxCalibrate()
+{
+ if ((millis() - startTime) < 2000 && sampleCount < maxSamples) {
+ readThrottleValues();
+ } else {
+ displayCalibratedValues(false);
+
+ // take some stats before normalizing min/max
+ int throttle1MinFluctuation = abs(throttle1MaxRest - throttle1MinRest);
+ int throttle2MinFluctuation = abs(throttle2MaxRest - throttle2MinRest);
+ int throttle1MaxFluctuation = abs(throttle1Max - throttle1Min);
+ int throttle2MaxFluctuation = abs(throttle2Max - throttle2Min);
+
+ // Determine throttle type based off min/max
+ if (throttle1MinRest > throttle1Min + maxThrottleReadingDeviationPercent) { // high to low pot
+ throttle1HighLow = true;
+ }
+
+ if (throttle2MinRest > throttle2Min + maxThrottleReadingDeviationPercent) { // high to low pot
+ throttle2HighLow = true;
+ }
+
+ // restore the true min
+ throttle1Min = throttle1MinRest;
+
+ if ((throttle1HighLow && !throttle2HighLow) || (throttle2HighLow && !throttle1HighLow)) {
+ throttle2Inverse = true;
+ }
+
+ // Detect grounded pin (always zero) or floating values which indicate no potentiometer provided
+ if ((throttle2MinRest == 0 && throttle2MaxRest == 0 && throttle2Min == INT16_MAX && throttle2Max == 0)
+ || (abs(throttle2MaxRest - throttle2Max) < maxThrottleReadingDeviationPercent
+ && abs(throttle2MinRest - throttle2Min) < maxThrottleReadingDeviationPercent)) {
+ potentiometerCount = 1;
+ } else {
+ potentiometerCount = 2;
+ }
+
+ // restore the true min/max for T2
+ if (throttle2Inverse) {
+ throttle2Max = throttle2MaxRest;
+ } else {
+ throttle2Min = throttle2MinRest;
+ }
+
+ logger.debug("Inverse: %s, throttle2Min: %d, throttle2Max: %d", (throttle2Inverse ? "true" : "false"), throttle2Min, throttle2Max);
+
+ // fluctuation percentages - make sure not to divide by zero
+ if (!(throttle1Max == throttle1Min))
+ {
+ throttle1MinFluctuationPercent = throttle1MinFluctuation * 100 / abs(throttle1Max - throttle1Min);
+ throttle1MaxFluctuationPercent = throttle1MaxFluctuation * 100 / abs(throttle1Max - throttle1Min);
+ }
+ else
+ {
+ throttle1MinFluctuationPercent = 0;
+ throttle1MaxFluctuationPercent = 0;
+ }
+
+ if (!(throttle2Max == throttle2Min))
+ {
+ throttle2MinFluctuationPercent = throttle2MinFluctuation * 100 / abs(throttle2Max - throttle2Min);
+ throttle2MaxFluctuationPercent = throttle2MaxFluctuation * 100 / abs(throttle2Max - throttle2Min);
}
+ else
+ {
+ throttle2MinFluctuationPercent = 0;
+ throttle2MaxFluctuationPercent = 0;
+ }
+
+ // Determine throttle subtype by examining the data sampled
+ for (int i = 0; i < sampleCount; i++) {
+ // normalize the values to a 0-1000 scale using the found min/max
+ uint16_t value1 = normalize(throttle1Values[i], throttle1Min, throttle1Max, 0, 1000);
+ uint16_t value2 = normalize(throttle2Values[i], throttle2Min, throttle2Max, 0, 1000);
+
+ // see if they match known subtypes
+ linearCount += checkLinear(value1, value2);
+ inverseCount += checkInverse(value1, value2);
+
+ //logger.debug("T1: %d, T2: %d = NT1: %d, NT2: %d, L: %d, I: %d", throttle1Values[i], throttle2Values[i], value1, value2, linearCount, inverseCount);
+ }
+
+ throttleSubType = 0;
+
+ if (potentiometerCount > 1) {
+ // For dual pots, we trust the detection of >75%
+ if ((linearCount * 100) / sampleCount > 75) {
+ throttleSubType = 1;
+ } else if ((inverseCount * 100) / sampleCount > 75) {
+ throttleSubType = 2;
+ }
+ } else {
+ // For single pots we use the high/low
+ if (throttle1HighLow) {
+ throttleSubType = 2;
+ } else {
+ throttleSubType = 1;
+ }
+ }
+
+ String type = "UNKNOWN";
+
+ if (throttleSubType == 1) {
+ type = "Linear";
+ } else if (throttleSubType == 2) {
+ type = "Inverse";
+ }
+
+ if (logger.isDebug()) {
+ logger.console("\n----- RAW values ----");
+
+ for (int i = 0; i < sampleCount; i++) {
+ logger.console("T1: %d, T2: %d", throttle1Values[i], throttle2Values[i]);
+ }
+ }
+
+ logger.console("\n=======================================");
+ logger.console("Detection complete");
+ logger.console("Num samples taken: %d", sampleCount);
+ logger.console("Num potentiometers found: %d", potentiometerCount);
+ logger.console("T1: %d to %d %s", (throttle1HighLow ? throttle1Max : throttle1Min), (throttle1HighLow ? throttle1Min : throttle1Max),
+ (throttle1HighLow ? "HIGH-LOW" : "LOW-HIGH"));
+ logger.console("T1: rest fluctuation %d%%, full throttle fluctuation %d%%", throttle1MinFluctuationPercent, throttle1MaxFluctuationPercent);
+
+ if (potentiometerCount > 1) {
+ logger.console("T2: %d to %d %s %s", (throttle2HighLow ? throttle2Max : throttle2Min), (throttle2HighLow ? throttle2Min : throttle2Max),
+ (throttle2HighLow ? "HIGH-LOW" : "LOW-HIGH"), (throttle2Inverse ? " (Inverse of T1)" : ""));
+ logger.console("T2: rest fluctuation %d%%, full throttle fluctuation %d%%", throttle2MinFluctuationPercent, throttle2MaxFluctuationPercent);
+ logger.console("Num linear throttle matches: %d", linearCount);
+ logger.console("Num inverse throttle matches: %d", inverseCount);
+ }
+
+ logger.console("Throttle type: %s", type.c_str());
+ logger.console("========================================");
+
+ // update the throttle's configuration (without storing it yet)
+ config->minimumLevel = throttle1Min;
+ config->maximumLevel = throttle1Max;
+ config->numberPotMeters = potentiometerCount;
+
+ if (config->numberPotMeters > 1) {
+ config->minimumLevel2 = throttle2Min;
+ config->maximumLevel2 = throttle2Max;
+ } else {
+ config->minimumLevel2 = 0;
+ config->maximumLevel2 = 0;
+ }
+
+ config->throttleSubType = throttleSubType;
+
+ // Done!
+ state = DoNothing;
+ tickHandler.detach(this);
+
+ // send updates to ichip wifi
+ deviceManager.sendMessage(DEVICE_WIFI, ICHIP2128, MSG_CONFIG_CHANGE, NULL);
+ }
}
/*
* Reset/initialize some values
*/
-void ThrottleDetector::resetValues() {
- throttle1Min = INT16_MAX;
- throttle1Max = 0;
- throttle2Min = INT16_MAX;
- throttle2Max = 0;
-
- potentiometerCount = 1;
- throttle1HighLow = false;
- throttle2HighLow = false;
- throttle2Inverse = false;
+void ThrottleDetector::resetValues()
+{
+ throttle1Min = INT16_MAX;
+ throttle1Max = 0;
+ throttle2Min = INT16_MAX;
+ throttle2Max = 0;
+
+ potentiometerCount = 1;
+ throttle1HighLow = false;
+ throttle2HighLow = false;
+ throttle2Inverse = false;
}
/*
* Reads values from the throttles.
*/
-void ThrottleDetector::readThrottleValues() {
- RawSignalData *rawSignal = throttle->acquireRawSignal();
- throttle1Values[sampleCount] = rawSignal->input1;
- throttle2Values[sampleCount] = rawSignal->input2;
- sampleCount++;
-
- // record the minimum sensor value
- if (rawSignal->input1 < throttle1Min) {
- throttle1Min = rawSignal->input1;
- }
-
- // record the maximum sensor value
- if (rawSignal->input1 > throttle1Max) {
- throttle1Max = rawSignal->input1;
- }
-
- // record the minimum sensor value
- if (rawSignal->input2 < throttle2Min) {
- throttle2Min = rawSignal->input2;
- }
-
- // record the maximum sensor value
- if (rawSignal->input2 > throttle2Max) {
- throttle2Max = rawSignal->input2;
- }
+void ThrottleDetector::readThrottleValues()
+{
+ RawSignalData *rawSignal = throttle->acquireRawSignal();
+ throttle1Values[sampleCount] = rawSignal->input1;
+ throttle2Values[sampleCount] = rawSignal->input2;
+ sampleCount++;
+
+ // record the minimum sensor value
+ if (rawSignal->input1 < throttle1Min) {
+ throttle1Min = rawSignal->input1;
+ }
+
+ // record the maximum sensor value
+ if (rawSignal->input1 > throttle1Max) {
+ throttle1Max = rawSignal->input1;
+ }
+
+ // record the minimum sensor value
+ if (rawSignal->input2 < throttle2Min) {
+ throttle2Min = rawSignal->input2;
+ }
+
+ // record the maximum sensor value
+ if (rawSignal->input2 > throttle2Max) {
+ throttle2Max = rawSignal->input2;
+ }
}
/*
@@ -355,11 +375,13 @@ void ThrottleDetector::readThrottleValues() {
* of each other (within a tolerance) otherwise returns 0
* Assumes the values are already mapped to a 0-1000 scale
*/
-int ThrottleDetector::checkLinear(uint16_t throttle1Value, uint16_t throttle2Value) {
- if ( abs(throttle1Value-throttle2Value) < maxThrottleReadingDeviationPercent)
- return 1;
+int ThrottleDetector::checkLinear(uint16_t throttle1Value, uint16_t throttle2Value)
+{
+ if (abs(throttle1Value - throttle2Value) < maxThrottleReadingDeviationPercent) {
+ return 1;
+ }
- return 0;
+ return 0;
}
/*
@@ -367,24 +389,28 @@ int ThrottleDetector::checkLinear(uint16_t throttle1Value, uint16_t throttle2Val
* of each other (within a tolerance) otherwise returns 0
* Assumes the values are already mapped to a 0-1000 scale
*/
-int ThrottleDetector::checkInverse(uint16_t throttle1Value, uint16_t throttle2Value) {
- if (abs(1000 - (throttle1Value+throttle2Value)) < maxThrottleReadingDeviationPercent)
- return 1;
+int ThrottleDetector::checkInverse(uint16_t throttle1Value, uint16_t throttle2Value)
+{
+ if (abs(1000 - (throttle1Value + throttle2Value)) < maxThrottleReadingDeviationPercent) {
+ return 1;
+ }
- return 0;
+ return 0;
}
-void ThrottleDetector::displayCalibratedValues(bool minPedal) {
- Logger::console("\nAt %s T1: %d to %d", (minPedal ? "MIN" : "MAX"), throttle1Min, throttle1Max);
- //if (potentiometerCount > 1)
- Logger::console(" T2: %d to %d", throttle2Min, throttle2Max);
- Logger::console("");
+void ThrottleDetector::displayCalibratedValues(bool minPedal)
+{
+ logger.console("\nAt %s T1: %d to %d", (minPedal ? "MIN" : "MAX"), throttle1Min, throttle1Max);
+ //if (potentiometerCount > 1)
+ logger.console(" T2: %d to %d", throttle2Min, throttle2Max);
+ logger.console("");
}
/**
* Map and constrain the value to the given range
*/
-uint16_t ThrottleDetector::normalize(uint16_t sensorValue, uint16_t sensorMin, uint16_t sensorMax, uint16_t constrainMin, uint16_t constrainMax) {
- int value = map(sensorValue, sensorMin, sensorMax, constrainMin, constrainMax);
- return constrain(value, constrainMin, constrainMax);
+uint16_t ThrottleDetector::normalize(uint16_t sensorValue, uint16_t sensorMin, uint16_t sensorMax, uint16_t constrainMin, uint16_t constrainMax)
+{
+ int value = map(sensorValue, sensorMin, sensorMax, constrainMin, constrainMax);
+ return constrain(value, constrainMin, constrainMax);
}
diff --git a/ThrottleDetector.h b/ThrottleDetector.h
index 0abbc7b..f403fcf 100644
--- a/ThrottleDetector.h
+++ b/ThrottleDetector.h
@@ -37,63 +37,64 @@
class Throttle;
-class ThrottleDetector : public TickObserver {
+class ThrottleDetector : public TickObserver
+{
public:
- ThrottleDetector(Throttle *throttle);
- ~ThrottleDetector();
- void handleTick();
- void detect();
+ ThrottleDetector(Throttle *throttle);
+ virtual ~ThrottleDetector();
+ void handleTick();
+ void detect();
private:
- enum DetectionState {
- DoNothing,
- DetectMinWait,
- DetectMinCalibrate,
- DetectMaxWait,
- DetectMaxCalibrate
- };
+ enum DetectionState {
+ DoNothing,
+ DetectMinWait,
+ DetectMinCalibrate,
+ DetectMaxWait,
+ DetectMaxCalibrate
+ };
- void detectMinWait();
- void detectMinCalibrate();
- void detectMaxWait();
- void detectMaxCalibrate();
- void displayCalibratedValues(bool minPedal);
- void resetValues();
- void readThrottleValues();
- int checkLinear(uint16_t, uint16_t);
- int checkInverse(uint16_t, uint16_t);
- uint16_t normalize(uint16_t sensorValue, uint16_t sensorMin, uint16_t sensorMax, uint16_t constrainMin, uint16_t constrainMax);
+ void detectMinWait();
+ void detectMinCalibrate();
+ void detectMaxWait();
+ void detectMaxCalibrate();
+ void displayCalibratedValues(bool minPedal);
+ void resetValues();
+ void readThrottleValues();
+ int checkLinear(uint16_t, uint16_t);
+ int checkInverse(uint16_t, uint16_t);
+ uint16_t normalize(uint16_t sensorValue, uint16_t sensorMin, uint16_t sensorMax, uint16_t constrainMin, uint16_t constrainMax);
- Throttle *throttle;
- PotThrottleConfiguration *config;
- DetectionState state;
- unsigned long startTime;
- int potentiometerCount; // the number of potentiometers detected
- uint16_t throttle1Min; // the minimum value of throttle1
- uint16_t throttle1Max; // the maximum value of throttle1
- uint16_t throttle2Min; // the minimum value of throttle2
- uint16_t throttle2Max; // the maximum value of throttle2
- uint8_t throttleSubType; // the throttle sub type
- bool throttle1HighLow; // true if throttle1 ranges from highest to lowest value as the pedal is pressed
- bool throttle2HighLow; // true if throttle2 ranges from highest to lowest value as the pedal is pressed
- bool throttle2Inverse; // true if throttle2 values are the opposite of the throttle1 values.
- int throttle1MinRest; // minimum sensor value at rest
- int throttle1MaxRest; // minimum sensor value at rest
- int throttle2MinRest; // minimum sensor value at rest
- int throttle2MaxRest; // maximum sensor value at rest
- int throttle1MinFluctuationPercent;
- int throttle1MaxFluctuationPercent;
- int throttle2MinFluctuationPercent;
- int throttle2MaxFluctuationPercent;
- int maxThrottleReadingDeviationPercent;
- // stats/counters when sampling
- static const int maxSamples = 300;
- int sampleCount;
- int linearCount;
- int inverseCount;
- uint16_t throttle1Values[maxSamples];
- uint16_t throttle2Values[maxSamples];
+ Throttle *throttle;
+ PotThrottleConfiguration *config;
+ DetectionState state;
+ unsigned long startTime;
+ int potentiometerCount; // the number of potentiometers detected
+ uint16_t throttle1Min; // the minimum value of throttle1
+ uint16_t throttle1Max; // the maximum value of throttle1
+ uint16_t throttle2Min; // the minimum value of throttle2
+ uint16_t throttle2Max; // the maximum value of throttle2
+ uint8_t throttleSubType; // the throttle sub type
+ bool throttle1HighLow; // true if throttle1 ranges from highest to lowest value as the pedal is pressed
+ bool throttle2HighLow; // true if throttle2 ranges from highest to lowest value as the pedal is pressed
+ bool throttle2Inverse; // true if throttle2 values are the opposite of the throttle1 values.
+ int throttle1MinRest; // minimum sensor value at rest
+ int throttle1MaxRest; // minimum sensor value at rest
+ int throttle2MinRest; // minimum sensor value at rest
+ int throttle2MaxRest; // maximum sensor value at rest
+ int throttle1MinFluctuationPercent;
+ int throttle1MaxFluctuationPercent;
+ int throttle2MinFluctuationPercent;
+ int throttle2MaxFluctuationPercent;
+ int maxThrottleReadingDeviationPercent;
+ // stats/counters when sampling
+ static const int maxSamples = 300;
+ int sampleCount;
+ int linearCount;
+ int inverseCount;
+ uint16_t throttle1Values[maxSamples];
+ uint16_t throttle2Values[maxSamples];
};
diff --git a/TickHandler.cpp b/TickHandler.cpp
index 1e96c01..30a9c4a 100644
--- a/TickHandler.cpp
+++ b/TickHandler.cpp
@@ -33,28 +33,18 @@
#include "TickHandler.h"
-TickHandler *TickHandler::tickHandler = NULL;
+TickHandler tickHandler;
-TickHandler::TickHandler() {
- for (int i = 0; i < NUM_TIMERS; i++) {
- timerEntry[i].interval = 0;
- for (int j = 0; j < CFG_TIMER_NUM_OBSERVERS; j++) {
- timerEntry[i].observer[j] = NULL;
- }
- }
-#ifdef CFG_TIMER_USE_QUEUING
- bufferHead = bufferTail = 0;
-#endif
-}
+TickHandler::TickHandler()
+{
+ for (int i = 0; i < NUM_TIMERS; i++) {
+ timerEntry[i].interval = 0;
-/*
- * Get a singleton instance of the TickHandler
- */
-TickHandler *TickHandler::getInstance() {
- if (tickHandler == NULL) {
- tickHandler = new TickHandler();
- }
- return tickHandler;
+ for (int j = 0; j < CFG_TIMER_NUM_OBSERVERS; j++) {
+ timerEntry[i].observer[j] = NULL;
+ }
+ }
+ bufferHead = bufferTail = 0;
}
/**
@@ -66,187 +56,257 @@ TickHandler *TickHandler::getInstance() {
* used. Then a free TickObserver slot (of max CFG_MAX_TICK_OBSERVERS) is looked up. If all went
* well, the timer is configured and (re)started.
*/
-void TickHandler::attach(TickObserver* observer, uint32_t interval) {
- int timer = findTimer(interval);
- if (timer == -1) {
- timer = findTimer(0); // no timer with given tick interval exist -> look for unused (interval == 0)
- if (timer == -1) {
- Logger::error("No free timer available for interval=%d", interval);
- return;
- }
- timerEntry[timer].interval = interval;
- }
-
- int observerIndex = findObserver(timer, 0);
- if (observerIndex == -1) {
- Logger::error("No free observer slot for timer %d with interval %d", timer, timerEntry[timer].interval);
- return;
- }
- timerEntry[timer].observer[observerIndex] = observer;
- Logger::debug("attached TickObserver (%X) as number %d to timer %d, %dus interval", observer, observerIndex, timer, interval);
-
- switch (timer) { // restarting a timer which would already be running is no problem (see DueTimer.cpp)
- case 0:
- Timer0.setPeriod(interval).attachInterrupt(timer0Interrupt).start();
- break;
- case 1:
- Timer1.setPeriod(interval).attachInterrupt(timer1Interrupt).start();
- break;
- case 2:
- Timer2.setPeriod(interval).attachInterrupt(timer2Interrupt).start();
- break;
- case 3:
- Timer3.setPeriod(interval).attachInterrupt(timer3Interrupt).start();
- break;
- case 4:
- Timer4.setPeriod(interval).attachInterrupt(timer4Interrupt).start();
- break;
- case 5:
- Timer5.setPeriod(interval).attachInterrupt(timer5Interrupt).start();
- break;
- case 6:
- Timer6.setPeriod(interval).attachInterrupt(timer6Interrupt).start();
- break;
- case 7:
- Timer7.setPeriod(interval).attachInterrupt(timer7Interrupt).start();
- break;
- case 8:
- Timer8.setPeriod(interval).attachInterrupt(timer8Interrupt).start();
- break;
- }
+void TickHandler::attach(TickObserver* observer, uint32_t interval)
+{
+ if (isAttached(observer, interval)) {
+ logger.warn("TickObserver %#x is already attached with interval %d", observer, interval);
+ return;
+ }
+
+ int timer = findTimer(interval);
+
+ if (timer == -1) {
+ timer = findTimer(0); // no timer with given tick interval exist -> look for unused (interval == 0)
+
+ if (timer == -1) {
+ logger.error("No free timer available for interval=%d", interval);
+ return;
+ }
+
+ timerEntry[timer].interval = interval;
+ }
+
+ int observerIndex = findObserver(timer, 0);
+
+ if (observerIndex == -1) {
+ logger.error("No free observer slot for timer %d with interval %d", timer, timerEntry[timer].interval);
+ return;
+ }
+
+ timerEntry[timer].observer[observerIndex] = observer;
+ logger.debug("attached TickObserver (%#x) as number %d to timer %d, %lu interval", observer, observerIndex, timer, interval);
+
+ switch (timer) { // restarting a timer which would already be running is no problem (see DueTimer.cpp)
+ case 0:
+ Timer0.setPeriod(interval).attachInterrupt(timer0Interrupt).start();
+ break;
+
+ case 1:
+ Timer1.setPeriod(interval).attachInterrupt(timer1Interrupt).start();
+ break;
+
+ case 2:
+ Timer2.setPeriod(interval).attachInterrupt(timer2Interrupt).start();
+ break;
+
+ case 3:
+ Timer3.setPeriod(interval).attachInterrupt(timer3Interrupt).start();
+ break;
+
+ case 4:
+ Timer4.setPeriod(interval).attachInterrupt(timer4Interrupt).start();
+ break;
+
+ case 5:
+ Timer5.setPeriod(interval).attachInterrupt(timer5Interrupt).start();
+ break;
+
+ case 6:
+ Timer6.setPeriod(interval).attachInterrupt(timer6Interrupt).start();
+ break;
+
+ case 7:
+ Timer7.setPeriod(interval).attachInterrupt(timer7Interrupt).start();
+ break;
+
+ case 8:
+ Timer8.setPeriod(interval).attachInterrupt(timer8Interrupt).start();
+ break;
+ }
+}
+
+/*
+ * Check if a observer is attached to this handler.
+ *
+ * \param observer - observer object to search
+ * \param interval - interval of the observer to search
+ */
+bool TickHandler::isAttached(TickObserver* observer, uint32_t interval)
+{
+ if (getInterval(observer) == interval) {
+ return true;
+ }
+ return false;
+}
+
+/*
+ * Try to find an observer and return its interval when it is attached.
+ * Returns 0 if the observer is not registered.
+ *
+ * \param observer - observer object to search
+ */
+uint32_t TickHandler::getInterval(TickObserver* observer)
+{
+ for (int timer = 0; timer < NUM_TIMERS; timer++) {
+ for (int observerIndex = 0; observerIndex < CFG_TIMER_NUM_OBSERVERS; observerIndex++) {
+ if (timerEntry[timer].observer[observerIndex] == observer) {
+ return timerEntry[timer].interval;
+ }
+ }
+ }
+ return 0;
}
/**
* Remove an observer from all timers where it was registered.
*/
-void TickHandler::detach(TickObserver* observer) {
- for (int timer = 0; timer < NUM_TIMERS; timer++) {
- for (int observerIndex = 0; observerIndex < CFG_TIMER_NUM_OBSERVERS; observerIndex++) {
- if (timerEntry[timer].observer[observerIndex] == observer) {
- Logger::debug("removing TickObserver (%X) as number %d from timer %d", observer, observerIndex, timer);
- timerEntry[timer].observer[observerIndex] = NULL;
- }
- }
- }
+void TickHandler::detach(TickObserver* observer)
+{
+ for (int timer = 0; timer < NUM_TIMERS; timer++) {
+ for (int observerIndex = 0; observerIndex < CFG_TIMER_NUM_OBSERVERS; observerIndex++) {
+ if (timerEntry[timer].observer[observerIndex] == observer) {
+ logger.debug("removing TickObserver (%#x) as number %d from timer %d", observer, observerIndex, timer);
+ timerEntry[timer].observer[observerIndex] = NULL;
+ }
+ }
+ }
}
/**
* Find a timer with a specified interval.
*/
-int TickHandler::findTimer(long interval) {
- for (int i = 0; i < NUM_TIMERS; i++) {
- if (timerEntry[i].interval == interval)
- return i;
- }
- return -1;
+int TickHandler::findTimer(long interval)
+{
+ for (int i = 0; i < NUM_TIMERS; i++) {
+ if (timerEntry[i].interval == interval) {
+ return i;
+ }
+ }
+
+ return -1;
}
/*
* Find a TickObserver in the list of a specific timer.
*/
-int TickHandler::findObserver(int timer, TickObserver *observer) {
- for (int i = 0; i < CFG_TIMER_NUM_OBSERVERS; i++) {
- if (timerEntry[timer].observer[i] == observer)
- return i;
- }
- return -1;
+int TickHandler::findObserver(int timer, TickObserver *observer)
+{
+ for (int i = 0; i < CFG_TIMER_NUM_OBSERVERS; i++) {
+ if (timerEntry[timer].observer[i] == observer) {
+ return i;
+ }
+ }
+
+ return -1;
}
-#ifdef CFG_TIMER_USE_QUEUING
/*
- * Check if a tick is available, forward it to registered observers.
+ * Process all queued tick observers in tickBuffer and call their handleTick() method.
+ * The entries were enqueued during an interrupt by handleInterrupt().
*/
-void TickHandler::process() {
- while (bufferHead != bufferTail) {
- tickBuffer[bufferTail]->handleTick();
- bufferTail = (bufferTail + 1) % CFG_TIMER_BUFFER_SIZE;
- //Logger::debug("process, bufferHead=%d bufferTail=%d", bufferHead, bufferTail);
- }
+void TickHandler::process()
+{
+ while (bufferHead != bufferTail) {
+ if (tickBuffer[bufferTail] == NULL) {
+ logger.error("tickBuffer pointer mismatch");
+ } else {
+// logger.debug("tickHandler->process, bufferHead=%d bufferTail=%d", bufferHead, bufferTail);
+ tickBuffer[bufferTail]->handleTick();
+ tickBuffer[bufferTail] = NULL;
+ }
+ bufferTail = (bufferTail + 1) % CFG_TIMER_BUFFER_SIZE;
+ }
}
-void TickHandler::cleanBuffer() {
- bufferHead = bufferTail = 0;
+void TickHandler::cleanBuffer()
+{
+ bufferHead = bufferTail = 0;
}
-#endif //CFG_TIMER_USE_QUEUING
-
/*
* Handle the interrupt of any timer.
- * All the registered TickObservers of the timer are called.
+ * All the registered TickObservers of the timer are added to tickBuffer (queue) to be processed outside of an interrupt (loop)
*/
-void TickHandler::handleInterrupt(int timerNumber) {
- for (int i = 0; i < CFG_TIMER_NUM_OBSERVERS; i++) {
- if (timerEntry[timerNumber].observer[i] != NULL) {
-#ifdef CFG_TIMER_USE_QUEUING
- tickBuffer[bufferHead] = timerEntry[timerNumber].observer[i];
- bufferHead = (bufferHead + 1) % CFG_TIMER_BUFFER_SIZE;
-//Logger::debug("bufferHead=%d, bufferTail=%d, observer=%d", bufferHead, bufferTail, timerEntry[timerNumber].observer[i]);
-#else
- timerEntry[timerNumber].observer[i]->handleTick();
-#endif //CFG_TIMER_USE_QUEUING
- }
- }
+void TickHandler::handleInterrupt(int timerNumber)
+{
+ for (int i = 0; i < CFG_TIMER_NUM_OBSERVERS; i++) {
+ if (timerEntry[timerNumber].observer[i] != NULL) {
+ tickBuffer[bufferHead] = timerEntry[timerNumber].observer[i];
+ bufferHead = (bufferHead + 1) % CFG_TIMER_BUFFER_SIZE;
+// logger.debug("tickHandler->handle bufferHead=%d, bufferTail=%d, observer=%d", bufferHead, bufferTail, timerEntry[timerNumber].observer[i]);
+ }
+ }
}
/*
* Interrupt function for Timer0
*/
-void timer0Interrupt() {
- TickHandler::getInstance()->handleInterrupt(0);
+void timer0Interrupt()
+{
+ tickHandler.handleInterrupt(0);
}
/*
* Interrupt function for Timer1
*/
-void timer1Interrupt() {
- TickHandler::getInstance()->handleInterrupt(1);
+void timer1Interrupt()
+{
+ tickHandler.handleInterrupt(1);
}
/*
* Interrupt function for Timer2
*/
-void timer2Interrupt() {
- TickHandler::getInstance()->handleInterrupt(2);
+void timer2Interrupt()
+{
+ tickHandler.handleInterrupt(2);
}
/*
* Interrupt function for Timer3
*/
-void timer3Interrupt() {
- TickHandler::getInstance()->handleInterrupt(3);
+void timer3Interrupt()
+{
+ tickHandler.handleInterrupt(3);
}
/*
* Interrupt function for Timer4
*/
-void timer4Interrupt() {
- TickHandler::getInstance()->handleInterrupt(4);
+void timer4Interrupt()
+{
+ tickHandler.handleInterrupt(4);
}
/*
* Interrupt function for Timer5
*/
-void timer5Interrupt() {
- TickHandler::getInstance()->handleInterrupt(5);
+void timer5Interrupt()
+{
+ tickHandler.handleInterrupt(5);
}
/*
* Interrupt function for Timer6
*/
-void timer6Interrupt() {
- TickHandler::getInstance()->handleInterrupt(6);
+void timer6Interrupt()
+{
+ tickHandler.handleInterrupt(6);
}
/*
* Interrupt function for Timer7
*/
-void timer7Interrupt() {
- TickHandler::getInstance()->handleInterrupt(7);
+void timer7Interrupt()
+{
+ tickHandler.handleInterrupt(7);
}
/*
* Interrupt function for Timer8
*/
-void timer8Interrupt() {
- TickHandler::getInstance()->handleInterrupt(8);
+void timer8Interrupt()
+{
+ tickHandler.handleInterrupt(8);
}
/*
* Default implementation of the TickObserver method. Must be overwritten
* by every sub-class.
*/
-void TickObserver::handleTick() {
- Logger::error("TickObserver does not implement handleTick()");
+void TickObserver::handleTick()
+{
+ logger.error("TickObserver does not implement handleTick()");
}
diff --git a/TickHandler.h b/TickHandler.h
index a54b1c0..20d2b1f 100644
--- a/TickHandler.h
+++ b/TickHandler.h
@@ -36,42 +36,42 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
#define NUM_TIMERS 9
-class TickObserver {
+class TickObserver // @suppress("Class has a virtual method and non-virtual destructor")
+{
public:
- virtual void handleTick();
+ virtual void handleTick();
};
-
-class TickHandler {
+class TickHandler
+{
public:
- static TickHandler *getInstance();
- void attach(TickObserver *observer, uint32_t interval);
- void detach(TickObserver *observer);
- void handleInterrupt(int timerNumber); // must be public when from the non-class functions
-#ifdef CFG_TIMER_USE_QUEUING
- void cleanBuffer();
- void process();
-#endif
+ TickHandler();
+ void attach(TickObserver *observer, uint32_t interval);
+ bool isAttached(TickObserver* observer, uint32_t interval);
+ uint32_t getInterval(TickObserver* observer);
+ void detach(TickObserver *observer);
+ void handleInterrupt(int timerNumber); // must be public when from the non-class functions
+ void cleanBuffer();
+ void process();
protected:
private:
- struct TimerEntry {
- long interval; // interval of timer
- TickObserver *observer[CFG_TIMER_NUM_OBSERVERS]; // array of pointers to observers with this interval
- };
- TimerEntry timerEntry[NUM_TIMERS]; // array of timer entries (9 as there are 9 timers)
- static TickHandler *tickHandler;
-#ifdef CFG_TIMER_USE_QUEUING
- TickObserver *tickBuffer[CFG_TIMER_BUFFER_SIZE];
- volatile uint16_t bufferHead, bufferTail;
-#endif
+ struct TimerEntry
+ {
+ long interval; // interval of timer
+ TickObserver *observer[CFG_TIMER_NUM_OBSERVERS]; // array of pointers to observers with this interval
+ };
+ TimerEntry timerEntry[NUM_TIMERS]; // array of timer entries (9 as there are 9 timers)
+ TickObserver *tickBuffer[CFG_TIMER_BUFFER_SIZE];
+ volatile uint16_t bufferHead, bufferTail;
- TickHandler();
- int findTimer(long interval);
- int findObserver(int timerNumber, TickObserver *observer);
+ int findTimer(long interval);
+ int findObserver(int timerNumber, TickObserver *observer);
};
+extern TickHandler tickHandler;
+
void timer0Interrupt();
void timer1Interrupt();
void timer2Interrupt();
diff --git a/ValueCache.cpp b/ValueCache.cpp
new file mode 100644
index 0000000..94a2ebe
--- /dev/null
+++ b/ValueCache.cpp
@@ -0,0 +1,106 @@
+/*
+ * cpp
+ *
+ * Created on: 10 Apr 2020
+ * Author: michaeln
+ */
+
+#include "ValueCache.h"
+
+ValueCache valueCache;
+
+ValueCache::ValueCache()
+{
+ clear();
+}
+
+/**
+ * \brief Initialize parameter cache so all params are sent when connecting
+ *
+ */
+void ValueCache::clear()
+{
+ systemState = 0;
+ timeRunning = millis(); // this way less important data is sent one second later
+ torqueActual = -1;
+ speedActual = -1;
+ throttle = -1;
+ torqueAvailable = 0;
+
+ dcVoltage = -1;
+ dcCurrent = -1;
+ acCurrent = -1;
+ temperatureMotor = -1;
+ temperatureController = -1;
+ mechanicalPower = 0;
+
+ bitfieldMotor = 0;
+ bitfieldBms = 0;
+ bitfieldIO = 0;
+
+ dcVoltageMin = 9999;
+ dcVoltageMax = 0;
+ dcCurrentMin = 0;
+ dcCurrentMax = 0;
+ temperatureMotorMax = 0;
+ temperatureControllerMax = 0;
+
+ dcDcHvVoltage = 0;
+ dcDcLvVoltage = 0;
+ dcDcHvCurrent = 0;
+ dcDcLvCurrent = 0;
+ dcDcTemperature = 0;
+
+ chargerInputVoltage = 0;
+ chargerInputCurrent = 0;
+ chargerBatteryVoltage = 0;
+ chargerBatteryCurrent = 0;
+ chargerTemperature = 0;
+ chargerInputCurrentTarget = -1;
+ chargeHoursRemain = 255;
+ chargeMinsRemain = 255;
+ chargeLevel = 0;
+
+ flowCoolant = 0;
+ flowHeater = 0;
+ heaterPower = 0;
+ for (int i = 0; i < CFG_NUMBER_BATTERY_TEMPERATURE_SENSORS; i++) {
+ temperatureBattery[i] = CFG_NO_TEMPERATURE_DATA;
+ }
+ temperatureCoolant = CFG_NO_TEMPERATURE_DATA;
+ temperatureHeater = CFG_NO_TEMPERATURE_DATA;
+ temperatureExterior = CFG_NO_TEMPERATURE_DATA;
+
+ powerSteering = false;
+ enableRegen = false;
+ enableHeater = false;
+ enableCreep = false;
+ cruiseControlSpeed = 0;
+ enableCruiseControl = false;
+
+ soc = 0;
+ dischargeLimit = 0;
+ chargeLimit = 0;
+ chargeAllowed = 0;
+ dischargeAllowed = 0;
+ lowestCellTemp = 0;
+ highestCellTemp = 0;
+ lowestCellVolts = 0;
+ highestCellVolts = 0;
+ averageCellVolts = 0;
+ deltaCellVolts = 0;
+ lowestCellResistance = 0;
+ highestCellResistance = 0;
+ averageCellResistance = 0;
+ deltaCellResistance = 0;
+ lowestCellTempId = 0;
+ highestCellTempId = 0;
+ lowestCellVoltsId = 0;
+ highestCellVoltsId = 0;
+ lowestCellResistanceId = 0;
+ highestCellResistanceId = 0;
+ packResistance = 0;
+ packHealth = 0;
+ packCycles = 0;
+ bmsTemperature = 0;
+}
diff --git a/ValueCache.h b/ValueCache.h
new file mode 100644
index 0000000..93b53d3
--- /dev/null
+++ b/ValueCache.h
@@ -0,0 +1,110 @@
+/*
+ * ValueCache.h
+ *
+ * Created on: 10 Apr 2020
+ * Author: michaeln
+ */
+
+#ifndef VALUECACHE_H_
+#define VALUECACHE_H_
+
+#include
+#include "config.h"
+
+/**
+ * Cache of param values to avoid sending an update unless changed
+ *
+ * NOTE: Keep the order and content in line with Websocket.cpp and WifiEsp32.cpp/.h and GEVCU_ESP32Web's code.
+ */
+class ValueCache
+{
+public:
+ ValueCache();
+ void clear();
+
+ uint8_t systemState;
+ uint32_t timeRunning;
+ int16_t torqueActual;
+ int16_t speedActual;
+ int16_t throttle;
+ int16_t torqueAvailable;
+
+ uint16_t dcVoltage;
+ int16_t dcCurrent;
+ int16_t acCurrent;
+ int16_t temperatureMotor;
+ int16_t temperatureController;
+ int16_t mechanicalPower;
+
+ uint32_t bitfieldMotor;
+ uint32_t bitfieldBms;
+ uint32_t bitfieldIO;
+
+ uint16_t dcVoltageMin;
+ uint16_t dcVoltageMax;
+ int16_t dcCurrentMin;
+ int16_t dcCurrentMax;
+ int16_t temperatureMotorMax;
+ int16_t temperatureControllerMax;
+
+ uint16_t dcDcHvVoltage;
+ uint16_t dcDcLvVoltage;
+ int16_t dcDcHvCurrent;
+ int16_t dcDcLvCurrent;
+ int16_t dcDcTemperature;
+
+ uint16_t chargerInputVoltage;
+ uint16_t chargerInputCurrent;
+ uint16_t chargerBatteryVoltage;
+ uint16_t chargerBatteryCurrent;
+ int16_t chargerTemperature;
+ int16_t chargerInputCurrentTarget;
+ uint8_t chargeHoursRemain;
+ uint8_t chargeMinsRemain;
+ uint16_t chargeLevel;
+
+ uint32_t flowCoolant;
+ uint32_t flowHeater;
+ uint16_t heaterPower;
+ int16_t temperatureBattery[CFG_NUMBER_BATTERY_TEMPERATURE_SENSORS];
+ int16_t temperatureCoolant;
+ int16_t temperatureHeater;
+ int16_t temperatureExterior;
+
+ bool powerSteering;
+ bool enableRegen;
+ bool enableHeater;
+ bool enableCreep;
+ int16_t cruiseControlSpeed;
+ bool enableCruiseControl;
+
+ uint16_t soc;
+ uint16_t dischargeLimit;
+ uint16_t chargeLimit;
+ bool chargeAllowed;
+ bool dischargeAllowed;
+ int16_t lowestCellTemp;
+ int16_t highestCellTemp;
+ uint16_t lowestCellVolts;
+ uint16_t highestCellVolts;
+ uint16_t averageCellVolts;
+ uint16_t deltaCellVolts;
+ uint16_t lowestCellResistance;
+ uint16_t highestCellResistance;
+ uint16_t averageCellResistance;
+ uint16_t deltaCellResistance;
+ uint8_t lowestCellTempId;
+ uint8_t highestCellTempId;
+ uint8_t lowestCellVoltsId;
+ uint8_t highestCellVoltsId;
+ uint8_t lowestCellResistanceId;
+ uint8_t highestCellResistanceId;
+ uint16_t packResistance;
+ uint8_t packHealth;
+ uint16_t packCycles;
+ uint8_t bmsTemperature;
+};
+
+extern ValueCache valueCache;
+
+#endif /* VALUECACHE_H_ */
diff --git a/WebSocket.cpp b/WebSocket.cpp
new file mode 100644
index 0000000..34e8819
--- /dev/null
+++ b/WebSocket.cpp
@@ -0,0 +1,748 @@
+/*
+ * WebSocket.cpp
+ *
+ * Class to handle web socket data for the dashboard
+ *
+ Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
+
+ 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 "WebSocket.h"
+
+static const char *webSocketKeyName = "Sec-WebSocket-Key";
+static const String websocketUid = "258EAFA5-E914-47DA-95CA-C5AB0DC85B11";
+
+/**
+ * \brief Constructor
+ *
+ */
+WebSocket::WebSocket()
+{
+ webSocketKey = NULL;
+ isFirst = true;
+ updateCounter = 0;
+ connected = false;
+ dcVoltageMin = 0;
+ dcVoltageMax = 0;
+ dcCurrentMin = 0;
+ dcCurrentMax = 0;
+ temperatureMotorMax = 0;
+ temperatureControllerMax = 0;
+ timeStamp = 0;
+}
+
+/**
+ * \brief Process requests from a web socket client
+ *
+ * Depending on connection state the header or the
+ * incoming data is processed.
+ *
+ * \param input incoming data
+ * \return the encoded socket response
+ */
+String WebSocket::processInput(char *input)
+{
+ if (connected) {
+ return processData(input);
+ } else {
+ // split the input into separate lines and process each line
+ char *line = strtok(input, "\r\n");
+ while (line != NULL) {
+ if (line[0] != 0) {
+ processConnectionRequest(line);
+ }
+ line = strtok(NULL, "\r\n");
+ }
+ return prepareConnectionRequestResponse();
+ }
+}
+
+/**
+ * \brief Process websocket connection request
+ *
+ * The method is called several times until the key is received.
+ *
+ * \param input incoming data
+ */
+void WebSocket::processConnectionRequest(char *input)
+{
+ // grab the key
+ char* key = strstr(input, webSocketKeyName);
+ if (key != NULL) {
+ webSocketKey = new String(key + strlen(webSocketKeyName) + 2);
+ logger.debug("websocket: found key: %s", webSocketKey->c_str());
+ }
+}
+
+/**
+ * \brief Prepare response to a connection request
+ *
+ * \return the response which is to be sent back to the browser
+ */
+String WebSocket::prepareConnectionRequestResponse() {
+ String response;
+
+ // they're done (empty line), send our response
+ if (webSocketKey != NULL) {
+ char acceptHash[128];
+ logger.debug("websocket: got a key and an empty line, let's go");
+ webSocketKey->concat(websocketUid); // append the UID to the key
+ // generate SHA1 hash of new key
+ Sha1.init();
+ Sha1.print(webSocketKey->c_str());
+ uint8_t* hash = Sha1.result();
+ // base64 encode the hash of the new key
+ base64_encode(acceptHash, (char*) (hash), 20);
+
+ response.concat("HTTP/1.1 101 Switching Protocols\r\n");
+ response.concat("Upgrade: websocket\r\n");
+ response.concat("Connection: Upgrade\r\n");
+ response.concat("Sec-WebSocket-Accept: ");
+ response.concat(acceptHash);
+ response.concat("\r\n\r\n");
+ valueCache.clear();
+ webSocketKey = NULL;
+ connected = true;
+ }
+ return response;
+}
+
+/**
+ * \brief Process incoming data from the client
+ *
+ * \param input the encoded data from the socket
+ * \return a response indicating if the connection should remain open
+ *
+ * Incoming data format:
+ 0 1 2 3
+ 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1
+ +-+-+-+-+-------+-+-------------+-------------------------------+
+ |F|R|R|R| opcode|M| Payload len | Extended payload length |
+ |I|S|S|S| (4) |A| (7) | (16/64) |
+ |N|V|V|V| |S| | (if payload len==126/127) |
+ | |1|2|3| |K| | |
+ +-+-+-+-+-------+-+-------------+ - - - - - - - - - - - - - - - +
+ | Extended payload length continued, if payload len == 127 |
+ + - - - - - - - - - - - - - - - +-------------------------------+
+ | |Masking-key, if MASK set to 1 |
+ +-------------------------------+-------------------------------+
+ | Masking-key (continued) | Payload Data |
+ +-------------------------------- - - - - - - - - - - - - - - - +
+ : Payload Data continued ... :
+ + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - +
+ | Payload Data continued ... |
+ +---------------------------------------------------------------+
+ *
+ */
+String WebSocket::processData(char *input)
+{
+ if (input == NULL || input[0] == 0) {
+ return "";
+ }
+
+ bool fin = (input[0] & 0x80) != 0;
+ int opcode = (input[0] & 0x0f);
+ bool mask = (input[1] & 0x80) != 0;
+ long payloadLength = input[1] & 0x7f;
+
+ logger.debug("websocket: fin: %#x, opcode: %#x, mask: %#x, length: %d", fin, opcode, mask, payloadLength);
+
+ uint8_t offset = 2;
+ if (payloadLength == 0x7e) { // 126 -> use next two bytes as unsigned 16bit length of payload
+ payloadLength = (input[offset] << 8) + input[offset + 1];
+ logger.debug("websocket: extended 16-bit length: %d", payloadLength);
+ offset += 2;
+ }
+ if (payloadLength == 0x7f) {
+ logger.warn("websocket: >64k frames not supported");
+ return "";
+ }
+
+ byte key[] = { input[offset], input[offset + 1], input[offset + 2], input[offset + 3] };
+ offset += 4;
+
+ if (mask) {
+ for (int i = 0; i < payloadLength; i++) {
+ input[offset + i] = (input[offset + i] ^ key[i % 4]);
+ }
+ input[offset + payloadLength] = 0;
+ }
+
+ switch (opcode) {
+ case OPCODE_CONTINUATION:
+ logger.warn("websocket: continuation frames not supported");
+ break;
+ case OPCODE_TEXT: {
+ char *text = input + offset;
+ bool flag = (strstr(text, "true") ? true : false);
+ char *equals = strchr(text, '=');
+ int16_t value = (equals ? atol(equals + 1) : 0);
+ if (strstr(text, "stopCharge")) {
+ status.setSystemState(Status::charged);
+ } else if (strstr(text, "cruiseToggle")) {
+ deviceManager.getMotorController()->cruiseControlToggle();
+ } else if (strstr(text, "cruise=")) {
+ if (text[7] == '-' || text[7] == '+') {
+ deviceManager.getMotorController()->cruiseControlAdjust(value);
+ } else {
+ deviceManager.getMotorController()->cruiseControlSetSpeed(value);
+ }
+ } else if (strstr(text, "regen=")) {
+ status.enableRegen = flag;
+ logger.debug("Regen is now switched %s", (flag ? "on" : "off"));
+ } else if (strstr(text, "creep=")) {
+ status.enableCreep = flag;
+ logger.debug("Creep is now switched %s", (flag ? "on" : "off"));
+ } else if (strstr(text, "ehps=")) {
+ systemIO.setPowerSteering(flag);
+ logger.debug("EHPS is now switched %s", (flag ? "on" : "off"));
+ } else if (strstr(text, "heater=")) {
+ systemIO.setEnableHeater(flag);
+ systemIO.setHeaterPump(flag);
+ logger.debug("Heater is now switched %s", (flag ? "on" : "off"));
+ } else if (strstr(text, "chargerInputCurrentTarget=")) {
+ logger.debug("Setting charge level to %.1f Amps", value);
+ deviceManager.getCharger()->setInputCurrentTarget(value * 10);
+ }
+ break;
+ }
+ case OPCODE_BINARY:
+ logger.warn("websocket: binary frames not supported");
+ break;
+ case OPCODE_CLOSE:
+ logger.info("websocket: close connection request");
+ connected = false;
+ return disconnect;
+ break;
+ case OPCODE_PING:
+ logger.warn("websocket: ping not supported: %d,%d,%d,%d,%d,%d: %s", input[0], input[1], input[2], input[3], input[4], input[5], input);
+ break;
+ case OPCODE_PONG:
+ break;
+ }
+ return "";
+}
+
+bool WebSocket::checkTime() {
+ //TODO with 115200 baud transferring 1kb requires 80ms. try higher baud rate with ichip
+ return (data.length() < 250);
+}
+
+/**
+ * \brief Prepare a JSON object which contains only changed values which are sent to the client
+ *
+ * (Processing time between 0-3ms)
+ *
+ * \return the encoded
+ */
+String WebSocket::generateUpdate()
+{
+ MotorController* motorController = deviceManager.getMotorController();
+ BatteryManager* batteryManager = deviceManager.getBatteryManager();
+ timeStamp = millis(); // init for checkTime()
+ data = String();
+ limits = String();
+ isFirst = true;
+
+ if (motorController) {
+ processValue(&valueCache.throttle, motorController->getThrottleLevel(), throttle, 10);
+ processValue(&valueCache.torqueActual, motorController->getTorqueActual(), torqueActual, 10);
+ if (updateCounter == 0 || updateCounter == 5) { // very fluctuating values which would unnecessarily strain the cpu (of a tablet)
+ processValue(&valueCache.speedActual, motorController->getSpeedActual(), speedActual);
+ if (batteryManager && batteryManager->hasPackVoltage()) {
+ processValue(&valueCache.dcVoltage, batteryManager->getPackVoltage(), dcVoltage, 10);
+ } else {
+ processValue(&valueCache.dcVoltage, motorController->getDcVoltage(), dcVoltage, 10);
+ processLimits(&dcVoltageMin, &dcVoltageMax, motorController->getDcVoltage(), dcVoltage);
+ }
+ if (batteryManager && batteryManager->hasPackCurrent()) {
+ processValue(&valueCache.dcCurrent, batteryManager->getPackCurrent(), dcCurrent, 10);
+ } else {
+ processValue(&valueCache.dcCurrent, motorController->getDcCurrent(), dcCurrent, 10);
+ processLimits(&dcCurrentMin, &dcCurrentMax, motorController->getDcCurrent(), dcCurrent);
+ }
+ processValue(&valueCache.temperatureMotor, motorController->getTemperatureMotor(), temperatureMotor, 10);
+ processLimits(NULL, &temperatureMotorMax, motorController->getTemperatureMotor(), temperatureMotor);
+ processValue(&valueCache.temperatureController, motorController->getTemperatureController(), temperatureController, 10);
+ processLimits(NULL, &temperatureControllerMax, motorController->getTemperatureController(), temperatureController);
+ processValue(&valueCache.cruiseControlSpeed, motorController->getCruiseControlSpeed(), cruiseControlSpeed);
+ processValue(&valueCache.enableCruiseControl, motorController->isCruiseControlEnabled(), enableCruiseControl);
+ }
+ }
+
+ if (checkTime()) {
+ processValue(&valueCache.bitfieldMotor, status.getBitFieldMotor(), bitfieldMotor);
+ processValue(&valueCache.bitfieldBms, status.getBitFieldBms(), bitfieldBms);
+ processValue(&valueCache.bitfieldIO, status.getBitFieldIO(), bitfieldIO);
+ }
+
+ if (timeStamp > valueCache.timeRunning + 900) { // just update this every second or so
+ valueCache.timeRunning = timeStamp;
+ addValue(timeRunning, getTimeRunning(), false);
+ processValue(&valueCache.systemState, (int16_t) status.getSystemState(), systemState);
+
+ if (batteryManager && checkTime()) {
+ if (batteryManager->hasSoc())
+ processValue(&valueCache.soc, (uint16_t)(batteryManager->getSoc() * 50), soc, 100);
+ if (batteryManager->hasDischargeLimit()) {
+ processValue(&valueCache.dischargeLimit, batteryManager->getDischargeLimit(), dischargeLimit);
+ if (batteryManager->getDischargeLimit() != dcCurrentMin || batteryManager->getChargeLimit() != dcCurrentMax) {
+ dcCurrentMax = batteryManager->getDischargeLimit();
+ dcCurrentMin = batteryManager->getChargeLimit() * -1;
+ addLimit((char *)String(dcCurrentMin).c_str(), (char *)String(dcCurrentMax).c_str(), dcCurrent);
+ }
+ } else {
+ processValue(&valueCache.dischargeAllowed, batteryManager->isDischargeAllowed(), dischargeAllowed);
+ }
+ if (batteryManager->hasChargeLimit())
+ processValue(&valueCache.chargeLimit, batteryManager->getChargeLimit(), chargeLimit);
+ else
+ processValue(&valueCache.chargeAllowed, batteryManager->isChargeAllowed(), chargeAllowed);
+ if (batteryManager->hasCellTemperatures() && checkTime()) {
+ processValue(&valueCache.lowestCellTemp, batteryManager->getLowestCellTemp(), lowestCellTemp, 10);
+ processValue(&valueCache.highestCellTemp, batteryManager->getHighestCellTemp(), highestCellTemp, 10);
+ processValue(&valueCache.lowestCellTempId, batteryManager->getLowestCellTempId(), lowestCellTempId);
+ processValue(&valueCache.highestCellTempId, batteryManager->getHighestCellTempId(), highestCellTempId);
+ }
+ if (batteryManager->hasCellVoltages() && checkTime()) {
+ processValue(&valueCache.lowestCellVolts, batteryManager->getLowestCellVolts(), lowestCellVolts, 10000);
+ processValue(&valueCache.highestCellVolts, batteryManager->getHighestCellVolts(), highestCellVolts, 10000);
+ processValue(&valueCache.averageCellVolts, batteryManager->getAverageCellVolts(), averageCellVolts, 10000);
+ processValue(&valueCache.deltaCellVolts, batteryManager->getHighestCellVolts() - batteryManager->getLowestCellVolts(), deltaCellVolts, 10000);
+ processValue(&valueCache.lowestCellVoltsId, batteryManager->getLowestCellVoltsId(), lowestCellVoltsId);
+ processValue(&valueCache.highestCellVoltsId, batteryManager->getHighestCellVoltsId(), highestCellVoltsId);
+ }
+ if (batteryManager->hasCellResistance() && checkTime()) {
+ processValue(&valueCache.lowestCellResistance, batteryManager->getLowestCellResistance(), lowestCellResistance, 100);
+ processValue(&valueCache.highestCellResistance, batteryManager->getHighestCellResistance(), highestCellResistance, 100);
+ processValue(&valueCache.averageCellResistance, batteryManager->getAverageCellResistance(), averageCellResistance, 100);
+ processValue(&valueCache.deltaCellResistance, (batteryManager->getHighestCellResistance() - batteryManager->getLowestCellResistance()), deltaCellResistance, 100);
+ processValue(&valueCache.lowestCellResistanceId, batteryManager->getLowestCellResistanceId(), lowestCellResistanceId);
+ processValue(&valueCache.highestCellResistanceId, batteryManager->getHighestCellResistanceId(), highestCellResistanceId);
+ }
+ if (checkTime()) {
+ if (batteryManager->hasPackResistance()) {
+ processValue(&valueCache.packResistance, batteryManager->getPackResistance(), packResistance);
+ }
+ if (batteryManager->hasPackHealth()) {
+ processValue(&valueCache.packHealth, batteryManager->getPackHealth(), packHealth);
+ }
+ if (batteryManager->hasPackCycles()) {
+ processValue(&valueCache.packCycles, batteryManager->getPackCycles(), packCycles);
+ }
+ }
+ processValue(&valueCache.bmsTemperature, batteryManager->getSystemTemperature(), bmsTemp);
+ }
+
+ DcDcConverter* dcDcConverter = deviceManager.getDcDcConverter();
+ if (dcDcConverter && checkTime()) {
+ processValue(&valueCache.dcDcHvVoltage, dcDcConverter->getHvVoltage(), dcDcHvVoltage, 10);
+ processValue(&valueCache.dcDcHvCurrent, dcDcConverter->getHvCurrent(), dcDcHvCurrent, 10);
+ processValue(&valueCache.dcDcLvVoltage, dcDcConverter->getLvVoltage(), dcDcLvVoltage, 10);
+ processValue(&valueCache.dcDcLvCurrent, dcDcConverter->getLvCurrent(), dcDcLvCurrent);
+ processValue(&valueCache.dcDcTemperature, dcDcConverter->getTemperature(), dcDcTemperature, 10);
+ }
+
+ if (status.getSystemState() == Status::charging || status.getSystemState() == Status::charged) {
+ Charger* charger = deviceManager.getCharger();
+ if (charger && checkTime()) {
+ processValue(&valueCache.chargerInputVoltage, charger->getInputVoltage(), chargerInputVoltage, 10);
+ processValue(&valueCache.chargerInputCurrent, charger->getInputCurrent(), chargerInputCurrent, 100);
+ processValue(&valueCache.chargerBatteryVoltage, charger->getBatteryVoltage(), chargerBatteryVoltage, 10);
+ processValue(&valueCache.chargerBatteryCurrent, charger->getBatteryCurrent(), chargerBatteryCurrent, 100);
+ processValue(&valueCache.chargerTemperature, charger->getTemperature(), chargerTemperature, 10);
+
+ uint16_t minutesRemaining = charger->calculateTimeRemaining();
+ processValue(&valueCache.chargeHoursRemain, minutesRemaining / 60, chargeHoursRemain);
+ processValue(&valueCache.chargeMinsRemain, minutesRemaining % 60, chargeMinsRemain);
+ if (batteryManager && batteryManager->hasSoc())
+ processValue(&valueCache.chargeLevel, batteryManager->getSoc() * 50, chargeLevel, 100);
+ processValue(&valueCache.chargerInputCurrentTarget, charger->calculateMaximumInputCurrent(), chargerInputCurrentTarget, 10);
+ }
+ }
+
+ if (checkTime()) {
+ processValue(&valueCache.heaterPower, status.heaterPower, heaterPower);
+ processValue(&valueCache.flowCoolant, status.flowCoolant * 6, flowCoolant, 100);
+ processValue(&valueCache.flowHeater, status.flowHeater * 6, flowHeater, 100);
+ for (int i = 0; i < CFG_NUMBER_BATTERY_TEMPERATURE_SENSORS; i++) {
+ processValue(&valueCache.temperatureBattery[i], status.temperatureBattery[i], temperatureBattery[i], 10);
+ }
+ processValue(&valueCache.temperatureCoolant, status.temperatureCoolant, temperatureCoolant, 10);
+ processValue(&valueCache.temperatureHeater, status.heaterTemperature, temperatureHeater);
+ if (status.temperatureExterior != CFG_NO_TEMPERATURE_DATA) {
+ processValue(&valueCache.temperatureExterior, status.temperatureExterior, temperatureExterior, 10);
+ }
+ }
+ if (checkTime()) {
+ processValue(&valueCache.enableRegen, status.enableRegen, enableRegen);
+ processValue(&valueCache.enableHeater, status.enableHeater, enableHeater);
+ processValue(&valueCache.powerSteering, status.powerSteering, powerSteering);
+ processValue(&valueCache.enableCreep, status.enableCreep, enableCreep);
+ }
+
+ if (limits.length() > 0) {
+ String out;
+ out.concat("{");
+ out.concat(limits.substring(0, limits.length() - 1));
+ out.concat("}");
+ addValue("limits", (char *)out.c_str(), true);
+ }
+ }
+
+ if (++updateCounter > 9) {
+ updateCounter = 0;
+ }
+
+ if (isFirst) { // return empty string -> nothing will be sent, lower resource usage
+ return data;
+ }
+ data.concat("\r}\r"); // close JSON object
+
+ return prepareWebSocketFrame(OPCODE_TEXT, data);
+}
+
+/**
+ * \brief Prepare JSON message for log message
+ *
+ * \param logLevel the level of the log entry
+ * \param deviceName name of the device which created the log entry
+ * \param message the log message
+ * \return the prepared log message which can be sent to the socket
+ *
+ */
+String WebSocket::generateLogEntry(String logLevel, String deviceName, String message)
+{
+ data = String();
+
+ if (!connected) {
+ return data;
+ }
+ data.concat("{\"logMessage\": {\"level\": \"");
+ data.concat(logLevel);
+ data.concat("\",\"message\": \"");
+ if (deviceName != NULL) {
+ data.concat(deviceName);
+ data.concat(": ");
+ }
+ data.concat(message);
+ data.concat("\"}}");
+
+ return prepareWebSocketFrame(OPCODE_TEXT, data);
+}
+
+/**
+ * \brief Wrap data into a web socket frame with the necessary header information (see Rfc 6455)
+ *
+ * \param opcode the opcode of the message (usually OPCODE_TEXT or OPCODE_BINARY)
+ * \param data the date to be encapsulated
+ * \return the web socket frame to be sent to the client
+ */
+String WebSocket::prepareWebSocketFrame(uint8_t opcode, String data)
+{
+ String frame = String();
+
+ frame.concat((char) (0b10000000 | opcode)); // FIN and opcode
+ if (data.length() < 126) {
+ frame.concat((char) (data.length() & 0x7f)); // mask = 0, length in one byte
+ } else if (data.length() < 0xffff) {
+ frame.concat((char) 0x7e); // mask = 0, length in following two bytes
+
+ // a dirty trick to prevent 0x00 bytes in the response string
+ while ((data.length() >> 8) == 0 || (data.length() & 0xff) == 0) {
+ data.concat(" ");
+ }
+
+ frame.concat((char) (data.length() >> 8)); // write high byte of length
+ frame.concat((char) (data.length() & 0xff)); // write low byte of length
+ } else {
+ // we won't send frames > 64k
+ }
+ frame.concat(data);
+ return frame;
+}
+
+/**
+ * \brief Add a value to the JSON data object
+ *
+ * It's important that the last entry has no trailing ',' sign and the strings
+ * are encapsulated with "" - otherwise the JSON parser will fail.
+ *
+ * \param key the name of the value to be added
+ * \param value the value to be added
+ * \param isNumeric an indication if the value is to be treated as numeric or string
+ */
+void WebSocket::addValue(const String key, char *value, bool isNumeric)
+{
+ if (isFirst) {
+ data.concat("{"); // open JSON object
+ isFirst = false;
+ } else {
+ data.concat(",");
+ }
+ data.concat("\"");
+ data.concat(key);
+ data.concat("\": ");
+ if (!isNumeric) {
+ data.concat("\"");
+ }
+ data.concat(value);
+ if (!isNumeric) {
+ data.concat("\"");
+ }
+}
+
+/**
+ * \brief Add a value to the response data if it has changed against the cached value
+ *
+ * \param cacheValue a pointer to the cached value against which the value is compared
+ * \param value the current value to be analyzed / added
+ * \param name the name of the value
+ */
+void WebSocket::processValue(uint8_t *cacheValue, uint8_t value, const String name)
+{
+ if (*cacheValue == value)
+ return;
+ *cacheValue = value;
+ sprintf(buffer, "%u", value);
+ addValue(name, buffer, true);
+}
+
+/**
+ * \brief Add a value to the response data if it has changed against the cached value
+ *
+ * \param cacheValue a pointer to the cached value against which the value is compared
+ * \param value the current value to be analyzed / added
+ * \param name the name of the value
+ */
+void WebSocket::processValue(int16_t *cacheValue, int16_t value, const String name)
+{
+ if (*cacheValue == value)
+ return;
+ *cacheValue = value;
+ sprintf(buffer, "%d", value);
+ addValue(name, buffer, true);
+}
+
+/**
+ * \brief Add a value to the response data if it has changed against the cached value
+ *
+ * \param cacheValue a pointer to the cached value against which the value is compared
+ * \param value the current value to be analyzed / added
+ * \param name the name of the value
+ */
+void WebSocket::processValue(uint16_t *cacheValue, uint16_t value, const String name)
+{
+ if (*cacheValue == value)
+ return;
+ *cacheValue = value;
+ sprintf(buffer, "%u", value);
+ addValue(name, buffer, true);
+}
+
+/**
+ * \brief Add a value to the response data if it has changed against the cached value
+ *
+ * \param cacheValue a pointer to the cached value against which the value is compared
+ * \param value the current value to be analyzed / added
+ * \param name the name of the value
+ */
+void WebSocket::processValue(int32_t *cacheValue, int32_t value, const String name)
+{
+ if (*cacheValue == value)
+ return;
+ *cacheValue = value;
+ sprintf(buffer, "%ld", value);
+ addValue(name, buffer, true);
+}
+
+/**
+ * \brief Add a value to the response data if it has changed against the cached value
+ *
+ * \param cacheValue a pointer to the cached value against which the value is compared
+ * \param value the current value to be analyzed / added
+ * \param name the name of the value
+ */
+void WebSocket::processValue(uint32_t *cacheValue, uint32_t value, const String name)
+{
+ if (*cacheValue == value)
+ return;
+ *cacheValue = value;
+ sprintf(buffer, "%lu", value);
+ addValue(name, buffer, true);
+}
+
+/**
+ * \brief Add a value to the response data if it has changed against the cached value
+ *
+ * \param cacheValue a pointer to the cached value against which the value is compared
+ * \param value the current value to be analyzed / added
+ * \param name the name of the value
+ * \param divisor by which the value should be divided to a float value
+ */
+void WebSocket::processValue(int16_t *cacheValue, int16_t value, const String name, int divisor)
+{
+ if (*cacheValue == value)
+ return;
+ *cacheValue = value;
+ char format[10];
+ sprintf(format, "%%.%ldf", round(log10(divisor)));
+ sprintf(buffer, format, static_cast(value) / divisor);
+ addValue(name, buffer, true);
+}
+
+/**
+ * \brief Add a value to the response data if it has changed against the cached value
+ *
+ * \param cacheValue a pointer to the cached value against which the value is compared
+ * \param value the current value to be analyzed / added
+ * \param name the name of the value
+ * \param divisor by which the value should be divided to a float value
+ */
+void WebSocket::processValue(uint16_t *cacheValue, uint16_t value, const String name, int divisor)
+{
+ if (*cacheValue == value)
+ return;
+ *cacheValue = value;
+ char format[10];
+ sprintf(format, "%%.%ldf", round(log10(divisor)));
+ sprintf(buffer, format, static_cast(value) / divisor);
+ addValue(name, buffer, true);
+}
+
+/**
+ * \brief Add a value to the response data if it has changed against the cached value
+ *
+ * \param cacheValue a pointer to the cached value against which the value is compared
+ * \param value the current value to be analyzed / added
+ * \param name the name of the value
+ * \param divisor by which the value should be divided to a float value
+ */
+void WebSocket::processValue(int32_t *cacheValue, int32_t value, const String name, int divisor)
+{
+ if (*cacheValue == value)
+ return;
+ *cacheValue = value;
+ char format[10];
+ sprintf(format, "%%.%ldf", round(log10(divisor)));
+ sprintf(buffer, format, static_cast(value) / divisor);
+ addValue(name, buffer, true);
+}
+
+/**
+ * \brief Add a value to the response data if it has changed against the cached value
+ *
+ * \param cacheValue a pointer to the cached value against which the value is compared
+ * \param value the current value to be analyzed / added
+ * \param name the name of the value
+ * \param divisor by which the value should be divided to a float value
+ */
+void WebSocket::processValue(uint32_t *cacheValue, uint32_t value, const String name, int divisor)
+{
+ if (*cacheValue == value)
+ return;
+ *cacheValue = value;
+
+ char format[10];
+ sprintf(format, "%%.%ldf", round(log10(divisor)));
+ sprintf(buffer, format, static_cast(value) / divisor);
+ addValue(name, buffer, true);
+}
+
+/**
+ * \brief Add a value to the response data if it has changed against the cached value
+ *
+ * \param cacheValue a pointer to the cached value against which the value is compared
+ * \param value the current value to be analyzed / added
+ * \param name the name of the value
+ */
+void WebSocket::processValue(bool *cacheValue, bool value, const String name)
+{
+ if (*cacheValue == value)
+ return;
+ *cacheValue = value;
+ strcpy(buffer, (value ? "true" : "false"));
+ addValue(name, buffer, true);
+}
+
+void WebSocket::processLimits(int16_t *min, int16_t *max, int16_t value, const String name) {
+ if (min && *min > value) {
+ *min = value;
+ sprintf(buffer, "%d", value);
+ addLimit(buffer, NULL, name);
+ }
+ if (max && value > *max) {
+ *max = value;
+ sprintf(buffer, "%d", value);
+ addLimit(NULL, buffer, name);
+ }
+}
+
+void WebSocket::processLimits(uint16_t *min, uint16_t *max, uint16_t value, const String name) {
+ if (min && *min > value) {
+ *min = value;
+ sprintf(buffer, "%u", value);
+ addLimit(buffer, NULL, name);
+ }
+ if (max && value > *max) {
+ *max = value;
+ sprintf(buffer, "%u", value);
+ addLimit(NULL, buffer, name);
+ }
+}
+
+void WebSocket::addLimit(char *min, char *max, const String name) {
+ if (!min && !max)
+ return;
+
+ limits.concat("\"");
+ limits.concat(name);
+ limits.concat("\": {");
+ if (min) {
+ limits.concat("\"min\": ");
+ limits.concat(min);
+ if (max)
+ limits.concat(",");
+ }
+ if (max) {
+ limits.concat("\"max\": ");
+ limits.concat(max);
+ }
+ limits.concat("},");
+}
+
+/**
+ * \brief Calculate the runtime in hh:mm:ss
+ *
+ * This runtime calculation is good for about 50 days of uptime.
+ * Of course, the sprintf is only good to 99 hours so that's a bit less time.
+ *
+ * \return the current time running in hh:mm:ss
+ */
+char *WebSocket::getTimeRunning()
+{
+ uint32_t ms = millis();
+ int seconds = (int) (ms / 1000) % 60;
+ int minutes = (int) ((ms / (1000 * 60)) % 60);
+ int hours = (int) ((ms / (1000 * 3600)) % 24);
+ sprintf(buffer, "%02d:%02d:%02d", hours, minutes, seconds);
+ return buffer;
+}
diff --git a/WebSocket.h b/WebSocket.h
new file mode 100644
index 0000000..55268ca
--- /dev/null
+++ b/WebSocket.h
@@ -0,0 +1,154 @@
+/*
+ * WebSocket.h
+ *
+ * Created on: 29 Mar 2016
+ * Author: michael
+ */
+
+#ifndef WEBSOCKET_H_
+#define WEBSOCKET_H_
+
+#include "SocketProcessor.h"
+#include "config.h"
+#include "MotorController.h"
+#include "Throttle.h"
+#include "Base64.h"
+#include "Sha1.h"
+#include "ValueCache.h"
+
+class WebSocket: public SocketProcessor
+{
+public:
+ WebSocket();
+ String generateUpdate();
+ String generateLogEntry(String logLevel, String deviceName, String message);
+ String processInput(char *input);
+
+private:
+ void processConnectionRequest(char *input);
+ String prepareConnectionRequestResponse();
+ String processData(char *input);
+ String prepareWebSocketFrame(uint8_t opcode, String data);
+ String getResponseKey(String key);
+ void processValue(uint8_t *cacheValue, uint8_t value, const String key);
+ void processValue(int16_t *cacheValue, int16_t value, const String key);
+ void processValue(uint16_t *cacheValue, uint16_t value, const String key);
+ void processValue(int32_t *cacheValue, int32_t value, const String key);
+ void processValue(uint32_t *cacheValue, uint32_t value, const String key);
+ void processValue(int16_t *cacheValue, int16_t value, const String key, int divisor);
+ void processValue(uint16_t *cacheValue, uint16_t value, const String key, int divisor);
+ void processValue(int32_t *cacheValue, int32_t value, const String key, int divisor);
+ void processValue(uint32_t *cacheValue, uint32_t value, const String key, int divisor);
+ void processValue(bool *cacheValue, bool value, const String name);
+ void addValue(const String key, char *value, bool isNumeric);
+ void processLimits(int16_t *min, int16_t *max, int16_t value, const String key);
+ void processLimits(uint16_t *min, uint16_t *max, uint16_t value, const String key);
+ void addLimit(char *min, char *max, const String name);
+ char* getTimeRunning();
+ bool checkTime();
+
+ enum
+ {
+ OPCODE_CONTINUATION = 0x0,
+ OPCODE_TEXT = 0x1,
+ OPCODE_BINARY = 0x2,
+ OPCODE_CLOSE = 0x8,
+ OPCODE_PING = 0x9,
+ OPCODE_PONG = 0xa
+ };
+ bool isFirst;
+ uint8_t updateCounter;
+ char buffer[30];
+ String *webSocketKey;
+ String data;
+ String limits;
+ bool connected;
+ // limits
+ uint16_t dcVoltageMin;
+ uint16_t dcVoltageMax;
+ int16_t dcCurrentMin;
+ int16_t dcCurrentMax;
+ int16_t temperatureMotorMax;
+ int16_t temperatureControllerMax;
+ uint32_t timeStamp;
+
+ const String disconnect = "_DISCONNECT_";
+
+ // status + dashboard
+ const String systemState = "systemState";
+ const String timeRunning = "timeRunning";
+ const String torqueActual = "torqueActual";
+ const String speedActual = "speedActual";
+ const String throttle = "throttle";
+
+ const String dcVoltage = "dcVoltage";
+ const String dcCurrent = "dcCurrent";
+ const String acCurrent = "acCurrent";
+ const String temperatureMotor = "temperatureMotor";
+ const String temperatureController = "temperatureController";
+ const String mechanicalPower = "mechanicalPower";
+
+ const String bitfieldMotor = "bitfieldMotor";
+ const String bitfieldBms = "bitfieldBms";
+ const String bitfieldIO = "bitfieldIO";
+
+ const String dcDcHvVoltage = "dcDcHvVoltage";
+ const String dcDcLvVoltage = "dcDcLvVoltage";
+ const String dcDcHvCurrent = "dcDcHvCurrent";
+ const String dcDcLvCurrent = "dcDcLvCurrent";
+ const String dcDcTemperature = "dcDcTemperature";
+
+ const String chargerInputVoltage = "chargerInputVoltage";
+ const String chargerInputCurrent = "chargerInputCurrent";
+ const String chargerBatteryVoltage = "chargerBatteryVoltage";
+ const String chargerBatteryCurrent = "chargerBatteryCurrent";
+ const String chargerTemperature = "chargerTemperature";
+ const String chargerInputCurrentTarget = "chargerInputCurrentTarget";
+ const String chargeHoursRemain = "chargeHoursRemain";
+ const String chargeMinsRemain = "chargeMinsRemain";
+ const String chargeLevel = "chargeLevel";
+
+ const String flowCoolant = "flowCoolant";
+ const String flowHeater = "flowHeater";
+ const String heaterPower = "heaterPower";
+ const String temperatureBattery[6] = { "temperatureBattery1", "temperatureBattery2", "temperatureBattery3", "temperatureBattery4",
+ "temperatureBattery5", "temperatureBattery6" };
+ const String temperatureCoolant = "temperatureCoolant";
+ const String temperatureHeater = "temperatureHeater";
+ const String temperatureExterior = "temperatureExterior";
+
+ const String powerSteering = "powerSteering";
+ const String enableRegen = "enableRegen";
+ const String enableHeater = "enableHeater";
+ const String enableCreep = "enableCreep";
+ const String cruiseControlSpeed = "cruiseSpeed";
+ const String enableCruiseControl = "enableCruiseControl";
+
+ const String soc = "soc";
+ const String dischargeLimit = "dischargeLimit";
+ const String chargeLimit = "chargeLimit";
+ const String chargeAllowed = "chargeAllowed";
+ const String dischargeAllowed = "dischargeAllowed";
+ const String lowestCellTemp = "lowestCellTemp";
+ const String highestCellTemp = "highestCellTemp";
+ const String lowestCellVolts = "lowestCellVolts";
+ const String highestCellVolts = "highestCellVolts";
+ const String averageCellVolts = "averageCellVolts";
+ const String deltaCellVolts = "deltaCellVolts";
+ const String lowestCellResistance = "lowestCellResistance";
+ const String highestCellResistance = "highestCellResistance";
+ const String averageCellResistance = "averageCellResistance";
+ const String deltaCellResistance = "deltaCellResistance";
+ const String lowestCellTempId = "lowestCellTempId";
+ const String highestCellTempId = "highestCellTempId";
+ const String lowestCellVoltsId = "lowestCellVoltsId";
+ const String highestCellVoltsId = "highestCellVoltsId";
+ const String lowestCellResistanceId = "lowestCellResistanceId";
+ const String highestCellResistanceId = "highestCellResistanceId";
+ const String packResistance = "packResistance";
+ const String packHealth = "packHealth";
+ const String packCycles = "packCycles";
+ const String bmsTemp = "bmsTemp";
+};
+
+#endif /* WEBSOCKET_H_ */
diff --git a/Wifi.cpp b/Wifi.cpp
new file mode 100644
index 0000000..39fdfca
--- /dev/null
+++ b/Wifi.cpp
@@ -0,0 +1,881 @@
+/*
+ * Wifi.cpp
+ *
+ * Created on: 31 Mar 2020
+ * Author: michaeln
+ */
+
+#include "Wifi.h"
+
+/*
+ * Constructor
+ */
+Wifi::Wifi() : Device()
+{
+ if (systemIO.getSystemType() == SystemIOConfiguration::GEVCU3 || systemIO.getSystemType() == SystemIOConfiguration::GEVCU4) {
+ serialInterface = &Serial2;
+ } else { //older hardware used this instead
+ serialInterface = &Serial3;
+ }
+}
+
+void Wifi::process() {
+}
+
+void Wifi::setParam(String key, String value) {
+}
+
+/**
+ * \brief Process the parameter update we received from a form submit.
+ *
+ * The response usually looks like this : key="value", so the key can be isolated
+ * by looking for the '=' sign and the leading/trailing '"' have to be ignored.
+ *
+ * \param key and value pair of changed parameter
+ */
+void Wifi::processParameterChange(String input)
+{
+ int pos = input.indexOf('=');
+ if (pos < 1) {
+ return;
+ }
+
+ String key = input.substring(0, pos);
+ String value = input.substring(pos + 1);
+
+ if (value.charAt(0) == '"' && value.charAt(value.length() - 1) == '"') {
+ value = value.substring(1, value.length() - 2); // cut leading/trailing '"' characters
+ }
+
+ processParameterChange(key, value);
+}
+
+/**
+ * \brief Process the parameter update.
+ *
+ * \param key of changed parameter
+ * \param value of changed parameter
+ */
+void Wifi::processParameterChange(String key, String value)
+{
+ if (key && value) {
+ if (processParameterChangeThrottle(key, value) || processParameterChangeBrake(key, value) ||
+ processParameterChangeMotor(key, value) || processParameterChangeCharger(key, value) ||
+ processParameterChangeDcDc(key, value) || processParameterChangeDevices(key, value) ||
+ processParameterChangeSystemIO(key, value)) {
+ if (logger.isDebug()) {
+ logger.debug(this, "parameter change: %s = %s", key.c_str(), value.c_str());
+ }
+ }
+ }
+}
+
+/**
+ * \brief Process a throttle parameter change
+ *
+ * \param key the name of the parameter
+ * \param value the value of the parameter
+ * \return true if the parameter was processed
+ */
+bool Wifi::processParameterChangeThrottle(String key, String value)
+{
+ Throttle *throttle = deviceManager.getAccelerator();
+
+ if (throttle) {
+ PotThrottleConfiguration *config = (PotThrottleConfiguration *) throttle->getConfiguration();
+
+ if(config) {
+ if (numberPotMeters.equals(key)) {
+ config->numberPotMeters = value.toInt();
+ } else if (throttleSubType.equals(key)) {
+ config->throttleSubType = value.toInt();
+ } else if (minimumLevel.equals(key)) {
+ config->minimumLevel = value.toInt();
+ } else if (minimumLevel2.equals(key)) {
+ config->minimumLevel2 = value.toInt();
+ } else if (maximumLevel.equals(key)) {
+ config->maximumLevel = value.toInt();
+ } else if (maximumLevel2.equals(key)) {
+ config->maximumLevel2 = value.toInt();
+ } else if (positionRegenMaximum.equals(key)) {
+ config->positionRegenMaximum = value.toDouble() * 10;
+ } else if (positionRegenMinimum.equals(key)) {
+ config->positionRegenMinimum = value.toDouble() * 10;
+ } else if (positionForwardMotionStart.equals(key)) {
+ config->positionForwardMotionStart = value.toDouble() * 10;
+ } else if (positionHalfPower.equals(key)) {
+ config->positionHalfPower = value.toDouble() * 10;
+ } else if (minimumRegen.equals(key)) {
+ config->minimumRegen = value.toInt();
+ } else if (maximumRegen.equals(key)) {
+ config->maximumRegen = value.toInt();
+ } else if (throttle->getId() == POTACCELPEDAL) {
+ if (throttleAdcPin1.equals(key)) {
+ config->AdcPin1 = value.toInt();
+ } else if (throttleAdcPin2.equals(key)) {
+ config->AdcPin2 = value.toInt();
+ } else {
+ return false;
+ }
+ } else {
+ return false;
+ }
+ throttle->saveConfiguration();
+ return true;
+ }
+ }
+ return false;
+}
+
+/**
+ * \brief Process a brake parameter change
+ *
+ * \param key the name of the parameter
+ * \param value the value of the parameter
+ * \return true if the parameter was processed
+ */
+bool Wifi::processParameterChangeBrake(String key, String value)
+{
+ Throttle *brake = deviceManager.getBrake();
+
+ if (brake) {
+ PotThrottleConfiguration *config = (PotThrottleConfiguration *) brake->getConfiguration();
+
+ if (config) {
+ if (brakeMinimumLevel.equals(key)) {
+ config->minimumLevel = value.toInt();
+ } else if (brakeMaximumLevel.equals(key)) {
+ config->maximumLevel = value.toInt();
+ } else if (brakeMinimumRegen.equals(key)) {
+ config->minimumRegen = value.toInt();
+ } else if (brakeMaximumRegen.equals(key)) {
+ config->maximumRegen = value.toInt();
+ } else if (brake->getId() == POTBRAKEPEDAL) {
+ if (brakeAdcPin.equals(key)) {
+ config->AdcPin1 = value.toInt();
+ } else {
+ return false;
+ }
+ } else {
+ return false;
+ }
+ brake->saveConfiguration();
+ return true;
+ }
+ }
+ return false;
+}
+
+/**
+ * \brief Process a motor parameter change
+ *
+ * \param key the name of the parameter
+ * \param value the value of the parameter
+ * \return true if the parameter was processed
+ */
+bool Wifi::processParameterChangeMotor(String key, String value)
+{
+ MotorController *motorController = deviceManager.getMotorController();
+
+ if (motorController) {
+ MotorControllerConfiguration *config = (MotorControllerConfiguration *) motorController->getConfiguration();
+
+ if (config) {
+ if (speedMax.equals(key)) {
+ config->speedMax = value.toInt();
+ } else if (torqueMax.equals(key)) {
+ config->torqueMax = value.toDouble() * 10;
+ } else if (nominalVolt.equals(key)) {
+ config->nominalVolt = value.toDouble() * 10;
+ } else if (motorMode.equals(key)) {
+ config->powerMode = (value.toInt() ? modeSpeed : modeTorque);
+ } else if (invertDirection.equals(key)) {
+ config->invertDirection = value.toInt();
+ } else if (slewRateMotor.equals(key)) {
+ config->slewRateMotor = value.toDouble() * 10;
+ } else if (slewRateRegen.equals(key)) {
+ config->slewRateRegen = value.toDouble() * 10;
+ } else if (maxMechanicalPowerMotor.equals(key)) {
+ config->maxMechanicalPowerMotor = value.toDouble() * 10;
+ } else if (maxMechanicalPowerRegen.equals(key)) {
+ config->maxMechanicalPowerRegen = value.toDouble() * 10;
+ } else if (creepLevel.equals(key)) {
+ config->creepLevel = value.toInt();
+ } else if (creepSpeed.equals(key)) {
+ config->creepSpeed = value.toInt();
+ } else if (brakeHold.equals(key)) {
+ config->brakeHold = value.toInt();
+ } else if (brakeHoldForceCoefficient.equals(key)) {
+ config->brakeHoldForceCoefficient = value.toInt();
+ } else if (reversePercent.equals(key)) {
+ config->reversePercent = value.toInt();
+ } else if (cruiseKp.equals(key)) {
+ config->cruiseKp = value.toDouble();
+ } else if (cruiseKi.equals(key)) {
+ config->cruiseKi = value.toDouble();
+ } else if (cruiseKd.equals(key)) {
+ config->cruiseKd = value.toDouble();
+ } else if (cruiseUseRpm.equals(key)) {
+ config->cruiseUseRpm = value.toInt();
+ } else if (cruiseLongPressDelta.equals(key)) {
+ config->cruiseLongPressDelta = value.toInt();
+ } else if (cruiseStepDelta.equals(key)) {
+ config->cruiseStepDelta = value.toInt();
+ } else if (motorController->getId() == BRUSA_DMC5) {
+ BrusaDMC5Configuration *dmc5Config = (BrusaDMC5Configuration *) config;
+ if (dcVoltLimitMotor.equals(key)) {
+ dmc5Config->dcVoltLimitMotor = value.toDouble() * 10;
+ } else if (dcVoltLimitRegen.equals(key)) {
+ dmc5Config->dcVoltLimitRegen = value.toDouble() * 10;
+ } else if (dcCurrentLimitMotor.equals(key)) {
+ dmc5Config->dcCurrentLimitMotor = value.toDouble() * 10;
+ } else if (dcCurrentLimitRegen.equals(key)) {
+ dmc5Config->dcCurrentLimitRegen = value.toDouble() * 10;
+ } else if (enableOscillationLimiter.equals(key)) {
+ dmc5Config->enableOscillationLimiter = value.toInt();
+ } else {
+ return false;
+ }
+ } else {
+ return false;
+ }
+ motorController->saveConfiguration();
+ return true;
+ }
+ }
+ return false;
+}
+
+/**
+ * \brief Process a charger parameter change
+ *
+ * \param key the name of the parameter
+ * \param value the value of the parameter
+ * \return true if the parameter was processed
+ */
+bool Wifi::processParameterChangeCharger(String key, String value)
+{
+ Charger *charger = deviceManager.getCharger();
+
+ if (charger) {
+ ChargerConfiguration *config = (ChargerConfiguration *) charger->getConfiguration();
+
+ if (config) {
+ if (maximumInputCurrent.equals(key)) {
+ config->maximumInputCurrent = value.toDouble() * 10;
+ } else if (initialInputCurrent.equals(key)) {
+ config->initialInputCurrent = value.toDouble() * 10;
+ } else if (constantCurrent.equals(key)) {
+ config->constantCurrent = value.toDouble() * 10;
+ } else if (constantVoltage.equals(key)) {
+ config->constantVoltage = value.toDouble() * 10;
+ } else if (terminateCurrent.equals(key)) {
+ config->terminateCurrent = value.toDouble() * 10;
+ } else if (minimumBatteryVoltage.equals(key)) {
+ config->minimumBatteryVoltage = value.toDouble() * 10;
+ } else if (maximumBatteryVoltage.equals(key)) {
+ config->maximumBatteryVoltage = value.toDouble() * 10;
+ } else if (minimumTemperature.equals(key)) {
+ config->minimumTemperature = value.toDouble() * 10;
+ } else if (maximumTemperature.equals(key)) {
+ config->maximumTemperature = value.toDouble() * 10;
+ } else if (maximumAmpereHours.equals(key)) {
+ config->maximumAmpereHours = value.toDouble() * 10;
+ } else if (maximumChargeTime.equals(key)) {
+ config->maximumChargeTime = value.toInt();
+ } else if (deratingRate.equals(key)) {
+ config->deratingRate = value.toDouble() * 10;
+ } else if (deratingReferenceTemperature.equals(key)) {
+ config->deratingReferenceTemperature = value.toDouble() * 10;
+ } else if (hystereseStopTemperature.equals(key)) {
+ config->hystereseStopTemperature = value.toDouble() * 10;
+ } else if (hystereseResumeTemperature.equals(key)) {
+ config->hystereseResumeTemperature = value.toDouble() * 10;
+ } else if (measureTime.equals(key)) {
+ config->measureTime = value.toInt();
+ } else if (measureCurrent.equals(key)) {
+ config->measureCurrent = value.toDouble() * 10;
+ } else if (voltageDrop.equals(key)) {
+ config->voltageDrop = value.toInt();
+ } else {
+ return false;
+ }
+ charger->saveConfiguration();
+ return true;
+ }
+ }
+ return false;
+}
+
+/**
+ * \brief Process a DCDC converter parameter change
+ *
+ * \param key the name of the parameter
+ * \param value the value of the parameter
+ * \return true if the parameter was processed
+ */
+bool Wifi::processParameterChangeDcDc(String key, String value)
+{
+ DcDcConverter *dcDcConverter = deviceManager.getDcDcConverter();
+
+ if (dcDcConverter) {
+ DcDcConverterConfiguration *config = (DcDcConverterConfiguration *) dcDcConverter->getConfiguration();
+
+ if (config) {
+ if (dcDcMode.equals(key)) {
+ config->mode = value.toInt();
+ } else if (lowVoltageCommand.equals(key)) {
+ config->lowVoltageCommand = value.toDouble() * 10;
+ } else if (hvUndervoltageLimit.equals(key)) {
+ config->hvUndervoltageLimit = value.toDouble();
+ } else if (lvBuckModeCurrentLimit.equals(key)) {
+ config->lvBuckModeCurrentLimit = value.toInt();
+ } else if (hvBuckModeCurrentLimit.equals(key)) {
+ config->hvBuckModeCurrentLimit = value.toDouble() * 10;
+ } else if (highVoltageCommand.equals(key)) {
+ config->highVoltageCommand = value.toInt();
+ } else if (lvUndervoltageLimit.equals(key)) {
+ config->lvUndervoltageLimit = value.toDouble() * 10;
+ } else if (lvBoostModeCurrentLimit.equals(key)) {
+ config->lvBoostModeCurrentLinit = value.toInt();
+ } else if (hvBoostModeCurrentLimit.equals(key)) {
+ config->hvBoostModeCurrentLimit = value.toDouble() * 10;
+ } else {
+ return false;
+ }
+ dcDcConverter->saveConfiguration();
+ return true;
+ }
+ }
+ return false;
+}
+
+/**
+ * \brief Process a system I/O parameter change
+ *
+ * \param key the name of the parameter
+ * \param value the value of the parameter
+ * \return true if the parameter was processed
+ */
+bool Wifi::processParameterChangeSystemIO(String key, String value)
+{
+ SystemIOConfiguration *config = (SystemIOConfiguration *) systemIO.getConfiguration();
+
+ if (logLevel.equals(key)) {
+ Logger::LogLevel logLevel = (Logger::LogLevel) value.toInt();
+ logger.setLoglevel(logLevel);
+ systemIO.setLogLevel(logLevel);
+ } else if (systemType.equals(key)) {
+ systemIO.setSystemType((SystemIOConfiguration::SystemType) value.toInt());
+ } else if (carType.equals(key)) {
+ config->carType = (SystemIOConfiguration::CarType) value.toInt();
+ } else if (prechargeMillis.equals(key)) {
+ config->prechargeMillis = value.toInt();
+ } else if (heaterTemperatureOn.equals(key)) {
+ config->heaterTemperatureOn = value.toInt();
+ } else if (coolingTempOn.equals(key)) {
+ config->coolingTempOn = value.toInt();
+ } else if (coolingTempOff.equals(key)) {
+ config->coolingTempOff = value.toInt();
+ } else if (enableInput.equals(key)) {
+ config->enableInput = value.toInt();
+ } else if (chargePowerAvailableInput.equals(key)) {
+ config->chargePowerAvailableInput = value.toInt();
+ } else if (interlockInput.equals(key)) {
+ config->interlockInput = value.toInt();
+ } else if (reverseInput.equals(key)) {
+ config->reverseInput = value.toInt();
+ } else if (absInput.equals(key)) {
+ config->absInput = value.toInt();
+ } else if (gearChangeInput.equals(key)) {
+ config->gearChangeInput = value.toInt();
+ } else if (prechargeRelayOutput.equals(key)) {
+ config->prechargeRelayOutput = value.toInt();
+ } else if (mainContactorOutput.equals(key)) {
+ config->mainContactorOutput = value.toInt();
+ } else if (secondaryContactorOutput.equals(key)) {
+ config->secondaryContactorOutput = value.toInt();
+ } else if (fastChargeContactorOutput.equals(key)) {
+ config->fastChargeContactorOutput = value.toInt();
+ } else if (enableMotorOutput.equals(key)) {
+ config->enableMotorOutput = value.toInt();
+ } else if (enableChargerOutput.equals(key)) {
+ config->enableChargerOutput = value.toInt();
+ } else if (enableDcDcOutput.equals(key)) {
+ config->enableDcDcOutput = value.toInt();
+ } else if (enableHeaterOutput.equals(key)) {
+ config->enableHeaterOutput = value.toInt();
+ } else if (heaterValveOutput.equals(key)) {
+ config->heaterValveOutput = value.toInt();
+ } else if (heaterPumpOutput.equals(key)) {
+ config->heaterPumpOutput = value.toInt();
+ } else if (coolingPumpOutput.equals(key)) {
+ config->coolingPumpOutput = value.toInt();
+ } else if (coolingFanOutput.equals(key)) {
+ config->coolingFanOutput = value.toInt();
+ } else if (brakeLightOutput.equals(key)) {
+ config->brakeLightOutput = value.toInt();
+ } else if (reverseLightOutput.equals(key)) {
+ config->reverseLightOutput = value.toInt();
+ } else if (powerSteeringOutput.equals(key)) {
+ config->powerSteeringOutput = value.toInt();
+ } else if (stateOfChargeOutput.equals(key)) {
+ config->stateOfChargeOutput = value.toInt();
+ } else if (statusLightOutput.equals(key)) {
+ config->statusLightOutput = value.toInt();
+ } else if (warningOutput.equals(key)) {
+ config->warningOutput = value.toInt();
+ } else if (powerLimitationOutput.equals(key)) {
+ config->powerLimitationOutput = value.toInt();
+ } else {
+ return false;
+ }
+ systemIO.saveConfiguration();
+ return true;
+}
+
+/**
+ * \brief Process a device specific parameter change
+ *
+ * \param key the name of the parameter
+ * \param value the value of the parameter
+ * \return true if the parameter was processed
+ */
+bool Wifi::processParameterChangeDevices(String key, String value)
+{
+ if (key.charAt(0) == 'x' && key.substring(1).toInt() > 0) {
+ long deviceId = strtol(key.c_str() + 1, 0, 16);
+ deviceManager.sendMessage(DEVICE_ANY, (DeviceId) deviceId, (value.toInt() ? MSG_ENABLE : MSG_DISABLE), NULL);
+ return true;
+ }
+ return false;
+}
+
+/*
+ * \brief Get parameters from devices and forward them to the wifi device.
+ */
+void Wifi::loadParameters()
+{
+ logger.info(this, "loading config params to wifi...");
+
+ loadParametersThrottle();
+ loadParametersBrake();
+ loadParametersMotor();
+ loadParametersCharger();
+ loadParametersDcDc();
+ loadParametersSystemIO();
+ loadParametersDevices();
+ loadParametersDashboard();
+}
+
+/**
+ * \brief Load throttle parameters to the wifi device
+ *
+ */
+void Wifi::loadParametersThrottle()
+{
+ Throttle *throttle = deviceManager.getAccelerator();
+
+ if (throttle) {
+ ThrottleConfiguration *throttleConfig = (ThrottleConfiguration *) throttle->getConfiguration();
+
+ if (throttleConfig) {
+ if (throttle->getId() == POTACCELPEDAL) {
+ PotThrottleConfiguration *potThrottleConfig = (PotThrottleConfiguration *) throttleConfig;
+ setParam(numberPotMeters, potThrottleConfig->numberPotMeters);
+ setParam(throttleSubType, potThrottleConfig->throttleSubType);
+ setParam(minimumLevel2, potThrottleConfig->minimumLevel2);
+ setParam(maximumLevel2, potThrottleConfig->maximumLevel2);
+ setParam(throttleAdcPin1, potThrottleConfig->AdcPin1);
+ setParam(throttleAdcPin2, potThrottleConfig->AdcPin2);
+ } else { // set reasonable values so the config page can be saved
+ setParam(numberPotMeters, (uint8_t) 1);
+ setParam(throttleSubType, (uint8_t)0);
+ setParam(minimumLevel2, (uint16_t) 50);
+ setParam(maximumLevel2, (uint16_t) 4095);
+ setParam(throttleAdcPin1, (uint8_t)CFG_OUTPUT_NONE);
+ setParam(throttleAdcPin2, (uint8_t)CFG_OUTPUT_NONE);
+ }
+ setParam(minimumLevel, throttleConfig->minimumLevel);
+ setParam(maximumLevel, throttleConfig->maximumLevel);
+ setParam(positionRegenMaximum, (uint16_t) (throttleConfig->positionRegenMaximum / 10));
+ setParam(positionRegenMinimum, (uint16_t) (throttleConfig->positionRegenMinimum / 10));
+ setParam(positionForwardMotionStart, (uint16_t) (throttleConfig->positionForwardMotionStart / 10));
+ setParam(positionHalfPower, (uint16_t) (throttleConfig->positionHalfPower / 10));
+ setParam(minimumRegen, throttleConfig->minimumRegen);
+ setParam(maximumRegen, throttleConfig->maximumRegen);
+ }
+ }
+}
+
+/**
+ * \brief Load brake parameters to the wifi device
+ *
+ */
+void Wifi::loadParametersBrake()
+{
+ Throttle *brake = deviceManager.getBrake();
+
+ if (brake) {
+ ThrottleConfiguration *brakeConfig = (ThrottleConfiguration *) brake->getConfiguration();
+
+ if (brake->getId() == POTBRAKEPEDAL) {
+ PotBrakeConfiguration *potBrakeConfig = (PotBrakeConfiguration *) brakeConfig;
+ setParam(brakeAdcPin, potBrakeConfig->AdcPin1);
+ } else {
+ setParam(brakeAdcPin, (uint8_t)CFG_OUTPUT_NONE);
+ }
+ if (brakeConfig) {
+ setParam(brakeMinimumLevel, brakeConfig->minimumLevel);
+ setParam(brakeMaximumLevel, brakeConfig->maximumLevel);
+ setParam(brakeMinimumRegen, brakeConfig->minimumRegen);
+ setParam(brakeMaximumRegen, brakeConfig->maximumRegen);
+ }
+ } else {
+ setParam(brakeMinimumLevel, (uint8_t)0);
+ setParam(brakeMaximumLevel, (uint8_t)100);
+ setParam(brakeMinimumRegen, (uint8_t)0);
+ setParam(brakeMaximumRegen, (uint8_t)0);
+ setParam(brakeAdcPin, (uint8_t)CFG_OUTPUT_NONE);
+ }
+}
+
+/**
+ * \brief Load motor parameters to the wifi device
+ *
+ */
+void Wifi::loadParametersMotor()
+{
+ MotorController *motorController = deviceManager.getMotorController();
+
+ if (motorController) {
+ MotorControllerConfiguration *config = (MotorControllerConfiguration *) motorController->getConfiguration();
+
+ if (config) {
+ setParam(speedMax, config->speedMax);
+ setParam(nominalVolt, config->nominalVolt / 10.0f, 1);
+ setParam(torqueMax, config->torqueMax / 10.0f, 1);
+ setParam(motorMode, (uint8_t) config->powerMode);
+ setParam(invertDirection, (uint8_t)(config->invertDirection ? 1 : 0));
+ setParam(slewRateMotor, config->slewRateMotor / 10.0f, 1);
+ setParam(slewRateRegen, config->slewRateRegen / 10.0f, 1);
+ setParam(maxMechanicalPowerMotor, config->maxMechanicalPowerMotor / 10.0f, 1);
+ setParam(maxMechanicalPowerRegen, config->maxMechanicalPowerRegen / 10.0f, 1);
+ setParam(creepLevel, config->creepLevel);
+ setParam(creepSpeed, config->creepSpeed);
+ setParam(brakeHold, config->brakeHold);
+ setParam(brakeHoldForceCoefficient, config->brakeHoldForceCoefficient);
+ setParam(reversePercent, config->reversePercent);
+ setParam(cruiseKp, config->cruiseKp);
+ setParam(cruiseKi, config->cruiseKi);
+ setParam(cruiseKd, config->cruiseKd);
+ setParam(cruiseUseRpm, (uint8_t)(config->cruiseUseRpm ? 1 : 0));
+ setParam(cruiseLongPressDelta, config->cruiseLongPressDelta);
+ setParam(cruiseStepDelta, config->cruiseStepDelta);
+
+ if (motorController->getId() == BRUSA_DMC5) {
+ BrusaDMC5Configuration *dmc5Config = (BrusaDMC5Configuration *) config;
+ setParam(dcVoltLimitMotor, dmc5Config->dcVoltLimitMotor / 10.0f, 1);
+ setParam(dcVoltLimitRegen, dmc5Config->dcVoltLimitRegen / 10.0f, 1);
+ setParam(dcCurrentLimitMotor, dmc5Config->dcCurrentLimitMotor / 10.0f, 1);
+ setParam(dcCurrentLimitRegen, dmc5Config->dcCurrentLimitRegen / 10.0f, 1);
+ setParam(enableOscillationLimiter, (uint8_t)(dmc5Config->enableOscillationLimiter ? 1 : 0));
+ }
+ String sets;
+ for (uint8_t i = 0; i < CFG_CRUISE_SIZE_SPEED_SET && config->speedSet[i] != 0; i++) {
+ if (i != 0) {
+ sets += ",";
+ }
+ sets += config->speedSet[i];
+ }
+ setParam(cruiseSpeedSet, sets);
+ setParam(cruiseSpeedStep, (uint16_t)300);
+ }
+ }
+}
+
+/**
+ * \brief Load charger parameters to the wifi device
+ *
+ */
+void Wifi::loadParametersCharger()
+{
+ Charger *charger = deviceManager.getCharger();
+
+ if (charger) {
+ ChargerConfiguration *config = (ChargerConfiguration *) charger->getConfiguration();
+
+ if (config) {
+ setParam(maximumInputCurrent, config->maximumInputCurrent / 10.0f, 1);
+ setParam(initialInputCurrent, config->initialInputCurrent / 10.0f, 1);
+ setParam(constantCurrent, config->constantCurrent / 10.0f, 1);
+ setParam(constantVoltage, config->constantVoltage / 10.0f, 1);
+ setParam(terminateCurrent, config->terminateCurrent / 10.0f, 1);
+ setParam(minimumBatteryVoltage, config->minimumBatteryVoltage / 10.0f, 1);
+ setParam(maximumBatteryVoltage, config->maximumBatteryVoltage / 10.0f, 1);
+ setParam(minimumTemperature, config->minimumTemperature / 10.0f, 1);
+ setParam(maximumTemperature, config->maximumTemperature / 10.0f, 1);
+ setParam(maximumAmpereHours, config->maximumAmpereHours / 10.0f, 1);
+ setParam(maximumChargeTime, config->maximumChargeTime);
+ setParam(deratingRate, config->deratingRate / 10.0f, 1);
+ setParam(deratingReferenceTemperature, config->deratingReferenceTemperature / 10.0f, 1);
+ setParam(hystereseStopTemperature, config->hystereseStopTemperature / 10.0f, 1);
+ setParam(hystereseResumeTemperature, config->hystereseResumeTemperature / 10.0f, 1);
+ setParam(measureTime, config->measureTime);
+ setParam(measureCurrent, config->measureCurrent / 10.0f, 1);
+ setParam(voltageDrop, config->voltageDrop);
+ }
+ }
+}
+
+/**
+ * \brief Load DCDC converter parameters to the wifi device
+ *
+ */
+void Wifi::loadParametersDcDc()
+{
+ DcDcConverter *dcDcConverter = deviceManager.getDcDcConverter();
+
+ if (dcDcConverter) {
+ DcDcConverterConfiguration *dcDcConfig = (DcDcConverterConfiguration *) dcDcConverter->getConfiguration();
+
+ if (dcDcConfig) {
+ setParam(dcDcMode, dcDcConfig->mode);
+ setParam(lowVoltageCommand, dcDcConfig->lowVoltageCommand / 10.0f, 1);
+ setParam(hvUndervoltageLimit, dcDcConfig->hvUndervoltageLimit);
+ setParam(lvBuckModeCurrentLimit, dcDcConfig->lvBuckModeCurrentLimit);
+ setParam(hvBuckModeCurrentLimit, dcDcConfig->hvBuckModeCurrentLimit / 10.0f, 1);
+ setParam(highVoltageCommand, dcDcConfig->highVoltageCommand);
+ setParam(lvUndervoltageLimit, dcDcConfig->lvUndervoltageLimit / 10.0f, 1);
+ setParam(lvBoostModeCurrentLimit, dcDcConfig->lvBoostModeCurrentLinit);
+ setParam(hvBoostModeCurrentLimit, dcDcConfig->hvBoostModeCurrentLimit / 10.0f, 1);
+ }
+ }
+}
+
+/**
+ * \brief Load system I/O parameters to the wifi device
+ *
+ */
+void Wifi::loadParametersSystemIO()
+{
+ SystemIOConfiguration *config = (SystemIOConfiguration *) systemIO.getConfiguration();
+
+ if (config) {
+ setParam(logLevel, (uint8_t) logger.getLogLevel());
+ setParam(systemType, (uint8_t) systemIO.getSystemType());
+ setParam(carType, (uint8_t)config->carType);
+ setParam(prechargeMillis, config->prechargeMillis);
+ setParam(heaterTemperatureOn, config->heaterTemperatureOn);
+ setParam(coolingTempOn, config->coolingTempOn);
+ setParam(coolingTempOff, config->coolingTempOff);
+
+ setParam(enableInput, config->enableInput);
+ setParam(chargePowerAvailableInput, config->chargePowerAvailableInput);
+ setParam(interlockInput, config->interlockInput);
+ setParam(reverseInput, config->reverseInput);
+ setParam(absInput, config->absInput);
+ setParam(gearChangeInput, config->gearChangeInput);
+
+ setParam(prechargeRelayOutput, config->prechargeRelayOutput);
+ setParam(mainContactorOutput, config->mainContactorOutput);
+ setParam(secondaryContactorOutput, config->secondaryContactorOutput);
+ setParam(fastChargeContactorOutput, config->fastChargeContactorOutput);
+
+ setParam(enableMotorOutput, config->enableMotorOutput);
+ setParam(enableChargerOutput, config->enableChargerOutput);
+ setParam(enableDcDcOutput, config->enableDcDcOutput);
+ setParam(enableHeaterOutput, config->enableHeaterOutput);
+
+ setParam(heaterValveOutput, config->heaterValveOutput);
+ setParam(heaterPumpOutput, config->heaterPumpOutput);
+ setParam(coolingPumpOutput, config->coolingPumpOutput);
+ setParam(coolingFanOutput, config->coolingFanOutput);
+
+ setParam(brakeLightOutput, config->brakeLightOutput);
+ setParam(reverseLightOutput, config->reverseLightOutput);
+ setParam(powerSteeringOutput, config->powerSteeringOutput);
+ setParam(warningOutput, config->warningOutput);
+ setParam(powerLimitationOutput, config->powerLimitationOutput);
+ setParam(stateOfChargeOutput, config->stateOfChargeOutput);
+ setParam(statusLightOutput, config->statusLightOutput);
+ }
+}
+
+/**
+ * \brief Load device specific parameters to the wifi device
+ *
+ */
+void Wifi::loadParametersDevices()
+{
+ Device *device = NULL;
+ char idHex[10];
+ int size = sizeof(deviceIds) / sizeof(DeviceId);
+
+ for (int i = 0; i < size; i++) {
+ sprintf(idHex, "x%x", deviceIds[i]);
+ device = deviceManager.getDeviceByID(deviceIds[i]);
+ if (device != NULL) {
+ setParam(idHex, (uint8_t)((device->isEnabled() == true) ? 1 : 0));
+ } else {
+ setParam(idHex, (uint8_t)0);
+ }
+ }
+}
+
+/**
+ * \brief Load dashboard related parameters to the wifi device
+ *
+ */
+void Wifi::loadParametersDashboard()
+{
+ MotorController *motorController = deviceManager.getMotorController();
+ Charger *charger = deviceManager.getCharger();
+
+ if (motorController) {
+ MotorControllerConfiguration *config = (MotorControllerConfiguration *) motorController->getConfiguration();
+
+ if (config) {
+ sprintf(buffer, "%d,%d", config->torqueMax / -10, config->torqueMax / 10);
+ setParam(torqueRange, buffer);
+ sprintf(buffer, "0,%d", config->speedMax);
+ setParam(rpmRange, buffer);
+ sprintf(buffer, "%d,%d", config->maxMechanicalPowerRegen / -10, config->maxMechanicalPowerMotor / 10);
+ setParam(powerRange, buffer);
+ } else {
+ setParam(torqueRange, "-300,300");
+ setParam(rpmRange, "0,8000");
+ setParam(powerRange, "-250,250");
+ }
+
+ //TODO make params configurable
+ setParam(currentRange, "-200,200");
+ setParam(batteryRangeLow, "297,357,368");
+ setParam(batteryRangeHigh, "387,405,418");
+ setParam(motorTempRange, "0,90,120");
+ setParam(controllerTempRange, "0,60,80");
+ setParam(socRange, "0,20,100");
+ }
+
+ if (charger) {
+ ChargerConfiguration *config = (ChargerConfiguration *)charger->getConfiguration();
+ sprintf(buffer, "0,%.1f", config->maximumInputCurrent / 10.0f);
+ setParam(chargeInputLevels, buffer);
+ } else {
+ setParam(chargeInputLevels, "4,128");
+ }
+}
+
+/**
+ * \brief Set a parameter to the given int32 value
+ *
+ * \param paramName the name of the parameter
+ * \param value the value to set
+ */
+void Wifi::setParam(String paramName, int32_t value)
+{
+ sprintf(buffer, "%ld", value);
+ setParam(paramName, buffer);
+}
+
+/**
+ * \brief Set a parameter to the given uint32 value
+ *
+ * \param paramName the name of the parameter
+ * \param value the value to set
+ */
+void Wifi::setParam(String paramName, uint32_t value)
+{
+ sprintf(buffer, "%lu", value);
+ setParam(paramName, buffer);
+}
+
+/**
+ * \brief Set a parameter to the given int16 value
+ *
+ * \param paramName the name of the parameter
+ * \param value the value to set
+ */
+void Wifi::setParam(String paramName, int16_t value)
+{
+ sprintf(buffer, "%d", value);
+ setParam(paramName, buffer);
+}
+
+/**
+ * \brief Set a parameter to the given uint16 value
+ *
+ * \param paramName the name of the parameter
+ * \param value the value to set
+ */
+void Wifi::setParam(String paramName, uint16_t value)
+{
+ sprintf(buffer, "%d", value);
+ setParam(paramName, buffer);
+}
+
+/**
+ * \brief Set a parameter to the given int8 value
+ *
+ * \param paramName the name of the parameter
+ * \param value the value to set
+ */
+void Wifi::setParam(String paramName, uint8_t value)
+{
+ sprintf(buffer, "%d", value);
+ setParam(paramName, buffer);
+}
+
+/**
+ * \brief Set a parameter to the given float value
+ *
+ * \param paramName the name of the parameter
+ * \param value the value to set
+ * \param precision the number of digits after the decimal sign
+ */
+void Wifi::setParam(String paramName, float value, int precision)
+{
+ char format[10];
+ sprintf(format, "%%.%df", precision);
+ sprintf(buffer, format, value);
+ setParam(paramName, buffer);
+}
+
+/**
+ * \brief Set a parameter to the given float value
+ *
+ * \param paramName the name of the parameter
+ * \param value the value to set
+ * \param precision the number of digits after the decimal sign
+ */
+void Wifi::setParam(String paramName, double value)
+{
+ sprintf(buffer, "%f", value);
+ setParam(paramName, buffer);
+}
+
+void Wifi::loadConfiguration()
+{
+// WifiConfiguration *config = (WifiConfiguration*) getConfiguration();
+
+ Device::loadConfiguration(); // call parent
+ logger.info(this, "Wifi configuration:");
+
+#ifdef USE_HARD_CODED
+
+ if (false) {
+#else
+ if (prefsHandler->checksumValid()) { //checksum is good, read in the values stored in EEPROM
+#endif
+ } else { //checksum invalid. Reinitialize values and store to EEPROM
+ }
+}
+
+void Wifi::saveConfiguration()
+{
+// WifiConfiguration *config = (WifiConfiguration*) getConfiguration();
+
+ Device::saveConfiguration(); // call parent
+
+ prefsHandler->saveChecksum();
+}
diff --git a/Wifi.h b/Wifi.h
new file mode 100644
index 0000000..860145f
--- /dev/null
+++ b/Wifi.h
@@ -0,0 +1,222 @@
+/*
+ * Wifi.h
+ *
+ * Parent class for Wifi devices
+ *
+ Copyright (c) 2020 Collin Kidder, Michael Neuweiler, Charles Galpin
+
+ 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 WIFI_H_
+#define WIFI_H_
+
+#include
+#include "config.h"
+#include "DeviceManager.h"
+#include "PotThrottle.h"
+#include "CanThrottle.h"
+#include "PotBrake.h"
+#include "Sys_Messages.h"
+#include "DeviceTypes.h"
+#include "ELM327Processor.h"
+#include "BrusaDMC5.h"
+#include "ValueCache.h"
+
+class WifiConfiguration: public DeviceConfiguration
+{
+};
+
+class Wifi: public Device
+{
+public:
+ Wifi();
+ virtual void process();
+
+ void loadConfiguration();
+ void saveConfiguration();
+
+protected:
+ void processParameterChange(String input);
+ void processParameterChange(String key, String value);
+ void loadParameters();
+ virtual void setParam(String paramName, String value);
+
+ USARTClass *serialInterface; //Allows to retarget the serial port we use
+
+private:
+ bool processParameterChangeThrottle(String key, String value);
+ bool processParameterChangeBrake(String key, String value);
+ bool processParameterChangeMotor(String key, String value);
+ bool processParameterChangeCharger(String key, String value);
+ bool processParameterChangeDcDc(String key, String value);
+ bool processParameterChangeSystemIO(String key, String value);
+ bool processParameterChangeDevices(String key, String value);
+ void loadParametersThrottle();
+ void loadParametersBrake();
+ void loadParametersMotor();
+ void loadParametersCharger();
+ void loadParametersDcDc();
+ void loadParametersSystemIO();
+ void loadParametersDevices();
+ void loadParametersDashboard();
+ void setParam(String paramName, int32_t value);
+ void setParam(String paramName, int16_t value);
+ void setParam(String paramName, uint32_t value);
+ void setParam(String paramName, uint16_t value);
+ void setParam(String paramName, uint8_t value);
+ void setParam(String paramName, float value, int precision);
+ void setParam(String paramName, double value);
+
+ char buffer[30]; // a buffer for various string conversions
+
+ /*
+ * The following constants are names of ichip variables (see xml files in website)
+ * They must be <=20 characters - this is why the content sometimes differs from the internal param name.
+ */
+
+ // configuration throttle + motor
+ const String numberPotMeters = "numberPotMeters";
+ const String throttleSubType = "throttleSubType";
+ const String minimumLevel = "minimumLevel";
+ const String minimumLevel2 = "minimumLevel2";
+ const String maximumLevel = "maximumLevel";
+ const String maximumLevel2 = "maximumLevel2";
+ const String positionRegenMaximum = "positionRegenMaximum";
+ const String positionRegenMinimum = "positionRegenMinimum";
+ const String positionForwardMotionStart = "positionForwardStart";
+ const String positionHalfPower = "positionHalfPower";
+ const String minimumRegen = "minimumRegen";
+ const String maximumRegen = "maximumRegen";
+ const String throttleAdcPin1 = "throttleAdcPin1";
+ const String throttleAdcPin2 = "throttleAdcPin2";
+ const String brakeAdcPin = "brakeAdcPin";
+ const String carType = "carType";
+ const String creepLevel = "creepLevel";
+ const String creepSpeed = "creepSpeed";
+ const String brakeMinimumLevel = "brakeMinimumLevel";
+ const String brakeMaximumLevel = "brakeMaximumLevel";
+ const String brakeMinimumRegen = "brakeMinimumRegen";
+ const String brakeMaximumRegen = "brakeMaximumRegen";
+ const String speedMax = "speedMax";
+ const String torqueMax = "torqueMax";
+ const String logLevel = "logLevel";
+ const String systemType = "systemType";
+ const String nominalVolt = "nominalVolt";
+ const String motorMode = "motorMode";
+ const String invertDirection = "invertDirection";
+ const String slewRateMotor = "slewRateMotor";
+ const String slewRateRegen = "slewRateRegen";
+ const String brakeHold = "brakeHold";
+ const String brakeHoldForceCoefficient = "brakeHoldForceCoef";
+ const String reversePercent = "reversePercent";
+ const String cruiseKp = "cruiseKp";
+ const String cruiseKi = "cruiseKi";
+ const String cruiseKd = "cruiseKd";
+ const String cruiseUseRpm = "cruiseUseRpm";
+ const String cruiseStepDelta = "cruiseStepDelta";
+ const String cruiseLongPressDelta = "cruiseLongPressDelta";
+ const String cruiseSpeedSet = "cruiseSpeedSet";
+ const String cruiseSpeedStep = "cruiseSpeedStep";
+
+ const String maxMechanicalPowerMotor = "maxMechPowerMotor";
+ const String maxMechanicalPowerRegen = "maxMechPowerRegen";
+ const String dcVoltLimitMotor = "dcVoltLimitMotor";
+ const String dcVoltLimitRegen = "dcVoltLimitRegen";
+ const String dcCurrentLimitMotor = "dcCurrentLimitMotor";
+ const String dcCurrentLimitRegen = "dcCurrentLimitRegen";
+ const String enableOscillationLimiter = "enableOscLimiter";
+ // input
+ const String gearChangeInput = "gearChange";
+ const String absInput = "abs";
+ const String reverseInput = "reverse";
+ const String enableInput = "enable";
+ const String chargePowerAvailableInput = "chargePwrAvail";
+ const String interlockInput = "interlock";
+ // output
+ const String brakeLightOutput = "brakeLight";
+ const String reverseLightOutput = "reverseLight";
+ const String powerSteeringOutput = "powerSteering";
+ const String stateOfChargeOutput = "stateOfCharge";
+ const String statusLightOutput = "statusLight";
+ const String prechargeMillis = "prechargeMillis";
+ const String prechargeRelayOutput = "prechargeRelay";
+ const String mainContactorOutput = "mainContactor";
+ const String secondaryContactorOutput = "secondaryCont";
+ const String enableMotorOutput = "enableMotor";
+ const String coolingFanOutput = "coolingFan";
+ const String coolingTempOn = "coolingTempOn";
+ const String coolingTempOff = "coolingTempOff";
+ const String fastChargeContactorOutput = "fastChargeCont";
+ const String enableChargerOutput = "enableCharger";
+ const String enableDcDcOutput = "enableDcDc";
+ const String enableHeaterOutput = "enableHeater";
+ const String heaterValveOutput = "heaterValve";
+ const String heaterPumpOutput = "heaterPump";
+ const String heaterTemperatureOn = "heaterTemperatureOn";
+ const String coolingPumpOutput = "coolingPump";
+ const String warningOutput = "warning";
+ const String powerLimitationOutput = "powerLimit";
+ // charger
+ const String maximumInputCurrent = "maximumInputCurrent";
+ const String initialInputCurrent = "initialInputCurrent";
+ const String constantCurrent = "constantCurrent";
+ const String constantVoltage = "constantVoltage";
+ const String terminateCurrent = "terminateCurrent";
+ const String minimumBatteryVoltage = "minBatteryVoltage";
+ const String maximumBatteryVoltage = "maxBatteryVoltage";
+ const String minimumTemperature = "minimumTemperature";
+ const String maximumTemperature = "maximumTemperature";
+ const String maximumAmpereHours = "maximumAmpereHours";
+ const String maximumChargeTime = "maximumChargeTime";
+ const String deratingRate = "deratingRate";
+ const String deratingReferenceTemperature = "deratingReferenceTmp";
+ const String hystereseStopTemperature = "hystereseStopTemp";
+ const String hystereseResumeTemperature = "hystereseResumeTemp";
+ const String measureTime = "measureTime";
+ const String measureCurrent = "measureCurrent";
+ const String voltageDrop = "voltageDrop";
+
+ // dc dc converter
+ const String dcDcMode = "dcDcMode";
+ const String lowVoltageCommand = "lowVoltageCommand";
+ const String hvUndervoltageLimit = "hvUndervoltageLimit";
+ const String lvBuckModeCurrentLimit = "lvBuckCurrentLimit";
+ const String hvBuckModeCurrentLimit = "hvBuckCurrentLimit";
+ const String highVoltageCommand = "highVoltageCommand";
+ const String lvUndervoltageLimit = "lvUndervoltageLimit";
+ const String lvBoostModeCurrentLimit = "lvBoostCurrentLimit";
+ const String hvBoostModeCurrentLimit = "hvBoostCurrentLimit";
+
+ const String torqueRange = "torqueRange";
+ const String rpmRange = "rpmRange";
+ const String currentRange = "currentRange";
+ const String motorTempRange = "motorTempRange";
+ const String controllerTempRange = "controllerTempRange";
+ const String batteryRangeLow = "batteryRangeLow";
+ const String batteryRangeHigh = "batteryRangeHigh";
+ const String socRange = "socRange";
+ const String powerRange = "powerRange";
+ const String chargeInputLevels = "chargeInputLevels";
+ const String overrideInputCurrent = "overrideInputCurrent";
+};
+
+#endif
diff --git a/WifiEsp32.cpp b/WifiEsp32.cpp
new file mode 100644
index 0000000..bf82844
--- /dev/null
+++ b/WifiEsp32.cpp
@@ -0,0 +1,616 @@
+/*
+ * Esp32Wifi.cpp
+ *
+ * Class to interface with the Esp32 based wifi adapter
+ *
+ Copyright (c) 2020 Collin Kidder, Michael Neuweiler, Charles Galpin
+
+ 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 "WifiEsp32.h"
+
+WifiEsp32::WifiEsp32() : Wifi()
+{
+ prefsHandler = new PrefHandler(ESP32WIFI);
+
+ serialInterface->begin(115200);
+
+ commonName = "WIFI (ESP32)";
+
+ didParamLoad = false;
+ connected = false;
+ inPos = outPos = 0;
+ timeStarted = 0;
+ timeHeartBeat = 0;
+ dataPointCount = 0;
+ psWritePtr = psReadPtr = 0;
+ updateCount = 0;
+ heartBeatEnabled = true;
+
+ pinMode(CFG_WIFI_ENABLE, OUTPUT);
+ digitalWrite(CFG_WIFI_ENABLE, LOW);
+}
+
+/**
+ * \brief Initialization of hardware and parameters
+ *
+ */
+void WifiEsp32::setup()
+{
+ digitalWrite(CFG_WIFI_ENABLE, HIGH);
+
+ didParamLoad = false;
+ connected = false;
+ inPos = outPos = 0;
+ timeStarted = timeHeartBeat = millis();
+ dataPointCount = 0;
+ psWritePtr = psReadPtr = 0;
+
+ // don't try to re-attach if called from reset() - to avoid warning message
+ if (!tickHandler.isAttached(this, CFG_TICK_INTERVAL_WIFI)) {
+ tickHandler.attach(this, CFG_TICK_INTERVAL_WIFI);
+ }
+
+ ready = true;
+ running = true;
+}
+
+/**
+ * \brief Tear down the device in a safe way.
+ *
+ */
+void WifiEsp32::tearDown()
+{
+ Device::tearDown();
+ digitalWrite(CFG_WIFI_ENABLE, LOW);
+}
+
+/**
+ * \brief Send a command to ichip
+ *
+ * A version which defaults to IDLE which is what most of the code used to assume.
+ *
+ * \param cmd the command string to be sent
+ */
+void WifiEsp32::sendCmd(String cmd)
+{
+ if (logger.isDebug()) {
+ logger.debug(this, "buffer: %s\n", cmd.c_str());
+ }
+ sendBuffer[psWritePtr++] = cmd;
+ if (psWritePtr >= CFG_SERIAL_SEND_BUFFER_SIZE) {
+ psWritePtr = 0;
+ }
+}
+
+/**
+ * \brief Try to send a buffered command to ESP32
+ */
+void WifiEsp32::sendBufferedCommand()
+{
+ if (psReadPtr != psWritePtr) {
+ serialInterface->print(sendBuffer[psReadPtr++]);
+ serialInterface->write(13);
+ if (psReadPtr >= CFG_SERIAL_SEND_BUFFER_SIZE) {
+ psReadPtr = 0;
+ }
+ }
+}
+
+/**
+ * \brief Perform regular tasks triggered by a timer
+ *
+ * Query for changed parameters of the config page, socket status
+ * and query for incoming data on sockets
+ *
+ */
+void WifiEsp32::handleTick()
+{
+ if (connected) {
+ sendSocketUpdate();
+ }
+
+ if (!didParamLoad && millis() > 3000 + timeStarted) {
+ loadParameters();
+ didParamLoad = true;
+ }
+
+ if (heartBeatEnabled && timeHeartBeat + 10000 < millis()) {
+ logger.error(this, "No heartbeat received from ESP32, resetting.");
+ reset();
+ }
+
+ if (!ready && !running && (timeHeartBeat + 1000 < millis())) {
+ logger.info("Re-initializing ESP32 after reset.");
+ setup(); // re-init after reset
+ }
+}
+
+/**
+ * \brief Handle a message sent by the DeviceManager
+ *
+ * \param messageType the type of the message
+ * \param message the message to be processed
+ */
+void WifiEsp32::handleMessage(uint32_t messageType, void* message)
+{
+ Device::handleMessage(messageType, message);
+
+ switch (messageType) {
+ case MSG_SET_PARAM: {
+ char **params = (char **) message;
+ setParam((char *) params[0], (char *) params[1]);
+ break;
+ }
+
+ case MSG_CONFIG_CHANGE:
+ loadParameters();
+ break;
+
+ case MSG_COMMAND:
+ sendCmd((char *) message);
+ break;
+
+ case MSG_LOG:
+ String *params = (String *) message;
+ sendLogMessage(params[0], params[1], params[2]);
+ break;
+ }
+}
+
+/**
+ * \brief Act on system state changes and send an update to the socket client
+ *
+ * \param oldState the previous system state
+ * \param newState the new system state
+ */
+void WifiEsp32::handleStateChange(Status::SystemState oldState, Status::SystemState newState)
+{
+ Device::handleStateChange(oldState, newState);
+ sendSocketUpdate();
+}
+
+/**
+ * \brief Process serial input waiting from the wifi module.
+ * or send next buffered command
+ *
+ * The method is called by the main loop
+ */
+void WifiEsp32::process()
+{
+ sendBufferedCommand();
+
+ int ch;
+ while (serialInterface->available()) {
+ ch = serialInterface->read();
+//SerialUSB.print((char)ch);
+ if (ch == -1) { //and there is no reason it should be -1
+ return;
+ }
+
+ if (ch == 13 || inPos > (CFG_WIFI_BUFFER_SIZE - 2)) {
+ inBuffer[inPos] = 0;
+ inPos = 0;
+
+ if (logger.isDebug()) {
+ logger.debug(this, "incoming: '%s'", inBuffer);
+ }
+ String input = inBuffer;
+ if (input.startsWith("cfg:")) {
+ processParameterChange(input.substring(4));
+ } else if (input.startsWith("cmd:")) {
+ processIncomingSocketCommand(input.substring(4));
+ } else if (input.startsWith("hb:")) {
+ timeHeartBeat = millis();
+ if (input.indexOf("stop") != -1) {
+ heartBeatEnabled = false;
+ } else if (input.indexOf("start") != -1) {
+ heartBeatEnabled = true;
+ }
+ }
+
+ return; // before processing the next line, return to the loop() to allow other devices to process.
+ } else if (ch != 10) { // don't add a LF character
+ inBuffer[inPos++] = (char) ch;
+ }
+ }
+}
+
+/**
+ * \brief Process incoming data from a socket
+ */
+void WifiEsp32::processIncomingSocketCommand(String input)
+{
+ logger.debug(this, "processing incoming socket command");
+
+ int pos = input.indexOf('=');
+ if (pos > 0) {
+ String key = input.substring(0, pos);
+ String value = input.substring(pos + 1);
+
+ if (key.equals("cruise")) {
+ int num = value.toInt();
+ if (value.charAt(0) == '-' || value.charAt(0) == '+') {
+ deviceManager.getMotorController()->cruiseControlAdjust(num);
+ } else {
+ deviceManager.getMotorController()->cruiseControlSetSpeed(num);
+ }
+ } else if (key.equals("regen")) {
+ status.enableRegen = value.equals("true");
+ logger.debug("Regen is now switched %s", (status.enableRegen ? "on" : "off"));
+ } else if (key.equals("creep")) {
+ status.enableCreep = value.equals("true");;
+ logger.debug("Creep is now switched %s", (status.enableCreep ? "on" : "off"));
+ } else if (key.equals("ehps")) {
+ systemIO.setPowerSteering(value.equals("true"));
+ logger.debug("EHPS is now switched %s", (status.powerSteering ? "on" : "off"));
+ } else if (key.equals("heater")) {
+ bool flag = value.equals("true");
+ systemIO.setEnableHeater(flag);
+ systemIO.setHeaterPump(flag);
+ logger.debug("Heater is now switched %s", (status.enableHeater ? "on" : "off"));
+ } else if (key.equals("chargerInputCurrentTarget")) {
+ logger.debug("Setting target charge level to %.1f Amps", value.toDouble());
+ deviceManager.getCharger()->setInputCurrentTarget(value.toDouble() * 10);
+ }
+ } else {
+ if (input.equals("stopCharge")) {
+ status.setSystemState(Status::charged);
+ } else if (input.equals("cruiseToggle")) {
+ deviceManager.getMotorController()->cruiseControlToggle();
+ } else if (input.equals("connected")) {
+ logger.debug("Client connected, clearing value cache");
+ valueCache.clear(); // new connection -> clear the cache to have all values sent
+ connected = true;
+ } else if (input.equals("disconnected")) {
+ logger.debug("Client disconnected");
+ connected = false;
+ } else if (input.equals("loadConfig")) {
+ didParamLoad = false;
+ } else if (input.equals("getLog")) {
+ logger.printHistory(*serialInterface);
+ }
+ }
+}
+
+/**
+ * \brief Set a parameter to the given string value
+ *
+ * \param paramName the name of the parameter
+ * \param value the value to set
+ */
+void WifiEsp32::setParam(String paramName, String value)
+{
+ if (logger.isDebug()) {
+ logger.debug(this, "setParam: cfg:%s=%s", paramName.c_str(), value.c_str());
+ }
+ sendCmd("cfg:" + paramName + "=" + value);
+}
+
+/**
+ * \brief send log message as JSON
+ *
+ * \param logLevel the level of the log entry
+ * \param deviceName name of the device which created the log entry
+ * \param message the log message
+ * \return the prepared log message which can be sent to the socket
+ *
+ */
+void WifiEsp32::sendLogMessage(String logLevel, String deviceName, String message)
+{
+ String data = "json:{\"logMessage\": {\"level\": \"";
+ data.concat(logLevel);
+ data.concat("\",\"message\": \"");
+ if (deviceName.length() > 0) {
+ data.concat(deviceName);
+ data.concat(": ");
+ }
+ data.concat(message);
+ data.concat("\"}}");
+
+ sendCmd(data);
+}
+
+/**
+ * \brief Send update to all active sockets
+ *
+ * The message to be sent is created by the assigned SocketProcessor
+ *
+ */
+void WifiEsp32::sendSocketUpdate()
+{
+ outPos = 0;
+ dataPointCount = 0;
+
+ prepareSystemData();
+ prepareMotorControllerData();
+ prepareBatteryManagerData();
+ if (updateCount == 0) {
+ prepareDcDcConverterData();
+ }
+ if (status.getSystemState() == Status::charging || status.getSystemState() == Status::charged) {
+ prepareChargerData();
+ }
+
+ if (outPos > 0) {
+ String header = "data:";
+ header.concat(dataPointCount);
+ serialInterface->print(header); // indicate that we will send a binary data stream of x bytes
+ serialInterface->write(13); // CR
+ serialInterface->write(outBuffer, outPos); // send the binary data
+ }
+ if (++updateCount > 5)
+ updateCount = 0;
+}
+
+void WifiEsp32::prepareMotorControllerData() {
+ MotorController* motorController = deviceManager.getMotorController();
+ BatteryManager* batteryManager = deviceManager.getBatteryManager();
+
+ if (motorController) {
+ processValue(&valueCache.bitfieldMotor, status.getBitFieldMotor(), bitfieldMotor);
+
+ processValue(&valueCache.torqueActual, motorController->getTorqueActual(), torqueActual);
+ processValue(&valueCache.torqueAvailable, motorController->getTorqueAvailable(), torqueAvailable);
+ processValue(&valueCache.speedActual, motorController->getSpeedActual(), speedActual);
+ processValue(&valueCache.throttle, motorController->getThrottleLevel(), throttle);
+ if (!batteryManager || !batteryManager->hasPackVoltage()) {
+ processValue(&valueCache.dcVoltage, motorController->getDcVoltage(), dcVoltage);
+ processLimits(&valueCache.dcVoltageMin, motorController->getDcVoltage(), dcVoltageMin, false);
+ processLimits(&valueCache.dcVoltageMax, motorController->getDcVoltage(), dcVoltageMax, true);
+ }
+ if (!batteryManager || !batteryManager->hasPackCurrent()) {
+ processValue(&valueCache.dcCurrent, motorController->getDcCurrent(), dcCurrent);
+ processLimits(&valueCache.dcCurrentMin, motorController->getDcCurrent(), dcCurrentMin, false);
+ processLimits(&valueCache.dcCurrentMax, motorController->getDcCurrent(), dcCurrentMax, true);
+ }
+ processValue(&valueCache.temperatureMotor, motorController->getTemperatureMotor(), temperatureMotor);
+ processLimits(&valueCache.temperatureMotorMax, motorController->getTemperatureMotor(), tempMotorMax, true);
+ processValue(&valueCache.temperatureController, motorController->getTemperatureController(), temperatureController);
+ processLimits(&valueCache.temperatureControllerMax, motorController->getTemperatureController(), tempControllerMax, true);
+ processValue(&valueCache.cruiseControlSpeed, motorController->getCruiseControlSpeed(), cruiseControlSpeed);
+ processValue(&valueCache.enableCruiseControl, motorController->isCruiseControlEnabled(), enableCruiseControl);
+ }
+}
+
+void WifiEsp32::prepareDcDcConverterData() {
+ DcDcConverter* dcDcConverter = deviceManager.getDcDcConverter();
+
+ if (dcDcConverter) {
+ processValue(&valueCache.dcDcHvVoltage, dcDcConverter->getHvVoltage(), dcDcHvVoltage);
+ processValue(&valueCache.dcDcHvCurrent, dcDcConverter->getHvCurrent(), dcDcHvCurrent);
+ processValue(&valueCache.dcDcLvVoltage, dcDcConverter->getLvVoltage(), dcDcLvVoltage);
+ processValue(&valueCache.dcDcLvCurrent, dcDcConverter->getLvCurrent(), dcDcLvCurrent);
+ processValue(&valueCache.dcDcTemperature, dcDcConverter->getTemperature(), dcDcTemperature);
+ }
+}
+
+void WifiEsp32::prepareChargerData() {
+ Charger* charger = deviceManager.getCharger();
+ BatteryManager* batteryManager = deviceManager.getBatteryManager();
+
+ if (charger) {
+ processValue(&valueCache.chargerInputVoltage, charger->getInputVoltage(), chargerInputVoltage);
+ processValue(&valueCache.chargerInputCurrent, charger->getInputCurrent(), chargerInputCurrent);
+ processValue(&valueCache.chargerBatteryVoltage, charger->getBatteryVoltage(), chargerBatteryVoltage);
+ processValue(&valueCache.chargerBatteryCurrent, charger->getBatteryCurrent(), chargerBatteryCurrent);
+ processValue(&valueCache.chargerTemperature, charger->getTemperature(), chargerTemperature);
+ processValue(&valueCache.chargerInputCurrentTarget, charger->calculateMaximumInputCurrent(), chargerInputCurrentTarget);
+
+ uint16_t minutesRemaining = charger->calculateTimeRemaining();
+ processValue(&valueCache.chargeHoursRemain, (uint8_t)(minutesRemaining / 60), chargeHoursRemain);
+ processValue(&valueCache.chargeMinsRemain, (uint8_t)(minutesRemaining % 60), chargeMinsRemain);
+ if (batteryManager && batteryManager->hasSoc())
+ processValue(&valueCache.chargeLevel, batteryManager->getSoc() * 50, chargeLevel);
+ }
+}
+
+void WifiEsp32::prepareSystemData() {
+ processValue(&valueCache.systemState, (uint8_t) status.getSystemState(), systemState);
+ processValue(&valueCache.bitfieldIO, status.getBitFieldIO(), bitfieldIO);
+
+ processValue(&valueCache.flowCoolant, status.flowCoolant * 6, flowCoolant);
+ processValue(&valueCache.flowHeater, status.flowHeater * 6, flowHeater);
+ processValue(&valueCache.heaterPower, status.heaterPower, heaterPower);
+ for (int i = 0; i < CFG_NUMBER_BATTERY_TEMPERATURE_SENSORS; i++) {
+ processValue(&valueCache.temperatureBattery[i], status.temperatureBattery[i], (DataPointCode)(temperatureBattery1 + i));
+ }
+ processValue(&valueCache.temperatureCoolant, status.temperatureCoolant, temperatureCoolant);
+ processValue(&valueCache.temperatureHeater, status.heaterTemperature, temperatureHeater);
+ if (status.temperatureExterior != CFG_NO_TEMPERATURE_DATA) {
+ processValue(&valueCache.temperatureExterior, status.temperatureExterior, temperatureExterior);
+ }
+
+ processValue(&valueCache.powerSteering, status.powerSteering, powerSteering);
+ processValue(&valueCache.enableRegen, status.enableRegen, enableRegen);
+ processValue(&valueCache.enableHeater, status.enableHeater, enableHeater);
+ processValue(&valueCache.enableCreep, status.enableCreep, enableCreep);
+}
+
+void WifiEsp32::prepareBatteryManagerData() {
+ BatteryManager* batteryManager = deviceManager.getBatteryManager();
+
+ if (batteryManager) {
+ processValue(&valueCache.bitfieldBms, status.getBitFieldBms(), bitfieldBms);
+
+ if (batteryManager->hasSoc())
+ processValue(&valueCache.soc, (uint16_t)(batteryManager->getSoc() * 50), soc);
+ if (batteryManager->hasPackVoltage()) {
+ processValue(&valueCache.dcVoltage, batteryManager->getPackVoltage(), dcVoltage);
+ processLimits(&valueCache.dcVoltageMin, batteryManager->getPackVoltage(), dcVoltageMin, false);
+ processLimits(&valueCache.dcVoltageMax, batteryManager->getPackVoltage(), dcVoltageMax, true);
+ }
+ if (batteryManager->hasPackCurrent())
+ processValue(&valueCache.dcCurrent, batteryManager->getPackCurrent(), dcCurrent);
+ if (batteryManager->hasDischargeLimit()) {
+ processValue(&valueCache.dischargeLimit, batteryManager->getDischargeLimit(), dischargeLimit);
+ processValue(&valueCache.dcCurrentMax, batteryManager->getDischargeLimit() * 10, dcCurrentMax);
+ } else {
+ processValue(&valueCache.dischargeAllowed, batteryManager->isDischargeAllowed(), dischargeAllowed);
+ }
+ if (batteryManager->hasChargeLimit()) {
+ processValue(&valueCache.chargeLimit, batteryManager->getChargeLimit(), chargeLimit);
+ processValue(&valueCache.dcCurrentMin, batteryManager->getChargeLimit() * -10, dcCurrentMin);
+ } else {
+ processValue(&valueCache.chargeAllowed, batteryManager->isChargeAllowed(), chargeAllowed);
+ }
+ if (batteryManager->hasCellTemperatures()) {
+ processValue(&valueCache.lowestCellTemp, batteryManager->getLowestCellTemp(), lowestCellTemp);
+ processValue(&valueCache.highestCellTemp, batteryManager->getHighestCellTemp(), highestCellTemp);
+ processValue(&valueCache.lowestCellTempId, batteryManager->getLowestCellTempId(), lowestCellTempId);
+ processValue(&valueCache.highestCellTempId, batteryManager->getHighestCellTempId(), highestCellTempId);
+ }
+ if (batteryManager->hasCellVoltages()) {
+ processValue(&valueCache.lowestCellVolts, batteryManager->getLowestCellVolts(), lowestCellVolts);
+ processValue(&valueCache.highestCellVolts, batteryManager->getHighestCellVolts(), highestCellVolts);
+ processValue(&valueCache.averageCellVolts, batteryManager->getAverageCellVolts(), averageCellVolts);
+ processValue(&valueCache.deltaCellVolts, batteryManager->getHighestCellVolts() - batteryManager->getLowestCellVolts(), deltaCellVolts);
+ processValue(&valueCache.lowestCellVoltsId, batteryManager->getLowestCellVoltsId(), lowestCellVoltsId);
+ processValue(&valueCache.highestCellVoltsId, batteryManager->getHighestCellVoltsId(), highestCellVoltsId);
+ }
+ if (batteryManager->hasCellResistance()) {
+ processValue(&valueCache.lowestCellResistance, batteryManager->getLowestCellResistance(), lowestCellResistance);
+ processValue(&valueCache.highestCellResistance, batteryManager->getHighestCellResistance(), highestCellResistance);
+ processValue(&valueCache.averageCellResistance, batteryManager->getAverageCellResistance(), averageCellResistance);
+ processValue(&valueCache.deltaCellResistance, (batteryManager->getHighestCellResistance() - batteryManager->getLowestCellResistance()), deltaCellResistance);
+ processValue(&valueCache.lowestCellResistanceId, batteryManager->getLowestCellResistanceId(), lowestCellResistanceId);
+ processValue(&valueCache.highestCellResistanceId, batteryManager->getHighestCellResistanceId(), highestCellResistanceId);
+ }
+ if (batteryManager->hasPackResistance()) {
+ processValue(&valueCache.packResistance, batteryManager->getPackResistance(), packResistance);
+ }
+ if (batteryManager->hasPackHealth()) {
+ processValue(&valueCache.packHealth, batteryManager->getPackHealth(), packHealth);
+ }
+ if (batteryManager->hasPackCycles()) {
+ processValue(&valueCache.packCycles, batteryManager->getPackCycles(), packCycles);
+ }
+ processValue(&valueCache.bmsTemperature, batteryManager->getSystemTemperature(), bmsTemperature);
+ }
+}
+
+void WifiEsp32::processValue(bool *cacheValue, bool value, DataPointCode code) {
+ if (*cacheValue == value)
+ return;
+ *cacheValue = value;
+
+ outBuffer[outPos++] = DATA_POINT_START;
+ outBuffer[outPos++] = code;
+ outBuffer[outPos++] = (value ? 1 : 0);
+ dataPointCount++;
+}
+
+void WifiEsp32::processValue(uint8_t *cacheValue, uint8_t value, DataPointCode code) {
+ if (*cacheValue == value)
+ return;
+ *cacheValue = value;
+
+ outBuffer[outPos++] = DATA_POINT_START;
+ outBuffer[outPos++] = code;
+ outBuffer[outPos++] = value;
+ dataPointCount++;
+}
+
+void WifiEsp32::processValue(uint16_t *cacheValue, uint16_t value, DataPointCode code) {
+ if (*cacheValue == value)
+ return;
+ *cacheValue = value;
+
+ outBuffer[outPos++] = DATA_POINT_START;
+ outBuffer[outPos++] = code;
+ outBuffer[outPos++] = (value & 0xFF00) >> 8;
+ outBuffer[outPos++] = value & 0x00FF;
+ dataPointCount++;
+}
+
+void WifiEsp32::processValue(int16_t *cacheValue, int16_t value, DataPointCode code) {
+ if (*cacheValue == value)
+ return;
+ *cacheValue = value;
+
+ outBuffer[outPos++] = DATA_POINT_START;
+ outBuffer[outPos++] = code;
+ outBuffer[outPos++] = (value & 0xFF00) >> 8;
+ outBuffer[outPos++] = value & 0x00FF;
+ dataPointCount++;
+}
+
+void WifiEsp32::processValue(uint32_t *cacheValue, uint32_t value, DataPointCode code) {
+ if (*cacheValue == value)
+ return;
+ *cacheValue = value;
+
+ outBuffer[outPos++] = DATA_POINT_START;
+ outBuffer[outPos++] = code;
+ outBuffer[outPos++] = (value & 0xFF000000) >> 24;
+ outBuffer[outPos++] = (value & 0x00FF0000) >> 16;
+ outBuffer[outPos++] = (value & 0x0000FF00) >> 8;
+ outBuffer[outPos++] = value & 0x000000FF;
+ dataPointCount++;
+}
+
+void WifiEsp32::processLimits(uint16_t *cacheValue, uint16_t value, DataPointCode code, boolean maximum) {
+ if (maximum && cacheValue && value > *cacheValue) {
+ processValue(cacheValue, value, code);
+ }
+ if (!maximum && cacheValue && value < *cacheValue) {
+ processValue(cacheValue, value, code);
+ }
+}
+
+void WifiEsp32::processLimits(int16_t *cacheValue, int16_t value, DataPointCode code, boolean maximum) {
+ if (maximum && cacheValue && value > *cacheValue) {
+ processValue(cacheValue, value, code);
+ }
+ if (!maximum && cacheValue && value < *cacheValue) {
+ processValue(cacheValue, value, code);
+ }
+}
+
+void WifiEsp32::reset() {
+ running = false;
+ ready = false;
+
+ digitalWrite(CFG_WIFI_ENABLE, LOW);
+ timeHeartBeat = millis();
+}
+
+
+/**
+ * \brief Get the device type
+ *
+ * \return the type of the device
+ */
+DeviceType WifiEsp32::getType()
+{
+ return DEVICE_WIFI;
+}
+
+/**
+ * \brief Get the device ID
+ *
+ * \return the ID of the device
+ */
+DeviceId WifiEsp32::getId()
+{
+ return ESP32WIFI;
+}
diff --git a/WifiEsp32.h b/WifiEsp32.h
new file mode 100644
index 0000000..23aa606
--- /dev/null
+++ b/WifiEsp32.h
@@ -0,0 +1,183 @@
+/*
+ * Esp32Wifi.h
+ *
+ * Class to interface with the ESP32 based wifi adapter
+ *
+ * Created: 3/31/2020
+ * Author: Michael Neuweiler
+
+ Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
+
+ 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 WIFIESP32_H_
+#define WIFIESP32_H_
+
+#include
+
+#include "ValueCache.h"
+#include "Wifi.h"
+#include "ValueCache.h"
+
+class WifiEsp32: public Wifi
+{
+public:
+ WifiEsp32();
+ void setup(); //initialization on start up
+ void tearDown();
+ void handleTick(); //periodic processes
+ void handleMessage(uint32_t messageType, void *message);
+ void handleStateChange(Status::SystemState, Status::SystemState);
+ DeviceType getType();
+ DeviceId getId();
+ void process();
+
+ enum DataPointCode // must match with DataPoints in ESP32Web's GevcuAdapter
+ {
+ systemState = 0,
+ torqueActual = 1,
+ speedActual = 2,
+ throttle = 3,
+ torqueAvailable = 4,
+
+ dcVoltage = 10,
+ dcCurrent = 11,
+ acCurrent = 12,
+ temperatureMotor = 13,
+ temperatureController = 14,
+ mechanicalPower = 15,
+
+ bitfieldMotor = 20,
+ bitfieldBms = 21,
+ bitfieldIO = 22,
+ dcCurrentMin = 23,
+ dcCurrentMax = 24,
+ dcVoltageMin = 25,
+ dcVoltageMax = 26,
+ tempMotorMax = 27,
+ tempControllerMax = 28,
+
+ dcDcHvVoltage = 30,
+ dcDcLvVoltage = 31,
+ dcDcHvCurrent = 32,
+ dcDcLvCurrent = 33,
+ dcDcTemperature = 34,
+
+ chargerInputVoltage = 40,
+ chargerInputCurrent = 41,
+ chargerBatteryVoltage = 42,
+ chargerBatteryCurrent = 43,
+ chargerTemperature = 44,
+ chargerInputCurrentTarget = 45,
+ chargeHoursRemain = 46,
+ chargeMinsRemain = 47,
+ chargeLevel = 48,
+
+ flowCoolant = 50,
+ flowHeater = 51,
+ heaterPower = 52,
+ temperatureBattery1 = 53,
+ temperatureBattery2 = 54,
+ temperatureBattery3 = 55,
+ temperatureBattery4 = 56,
+ temperatureBattery5 = 57,
+ temperatureBattery6 = 58,
+ temperatureCoolant = 59,
+ temperatureHeater = 60,
+ temperatureExterior = 61,
+
+ powerSteering = 70,
+ enableRegen = 71,
+ enableHeater = 72,
+ enableCreep = 73,
+ cruiseControlSpeed = 74,
+ enableCruiseControl = 75,
+
+ soc = 80,
+ dischargeLimit = 81,
+ chargeLimit = 82,
+ chargeAllowed = 83,
+ dischargeAllowed = 84,
+ lowestCellTemp = 85,
+ highestCellTemp = 86,
+ lowestCellVolts = 87,
+ highestCellVolts = 88,
+ averageCellVolts = 89,
+ deltaCellVolts = 90,
+ lowestCellResistance = 91,
+ highestCellResistance = 92,
+ averageCellResistance = 93,
+ deltaCellResistance = 94,
+ lowestCellTempId = 95,
+ highestCellTempId = 96,
+ lowestCellVoltsId = 97,
+ highestCellVoltsId = 98,
+ lowestCellResistanceId = 99,
+ highestCellResistanceId = 100,
+ packResistance = 101,
+ packHealth = 102,
+ packCycles = 103,
+ bmsTemperature = 104
+ };
+
+private:
+ void requestNextParam(); //get next changed parameter
+ void requestParamValue(String paramName); //try to retrieve the value of the given parameter
+ void setParam(String paramName, String value); //set the given parameter with the given string
+ void sendLogMessage(String logLevel, String deviceName, String message);
+ void sendCmd(String cmd);
+ void sendBufferedCommand();
+ void sendSocketUpdate();
+ void processStartSocketListenerRepsonse();
+ void processActiveSocketListResponse();
+ void processIncomingSocketCommand(String data);
+ void processSocketSendResponse();
+ void prepareMotorControllerData();
+ void prepareDcDcConverterData();
+ void prepareChargerData();
+ void prepareSystemData();
+ void prepareBatteryManagerData();
+ void processValue(bool *cacheValue, bool value, DataPointCode code);
+ void processValue(uint8_t *cacheValue, uint8_t value, DataPointCode code);
+ void processValue(uint16_t *cacheValue, uint16_t value, DataPointCode code);
+ void processValue(int16_t *cacheValue, int16_t value, DataPointCode code);
+ void processValue(uint32_t *cacheValue, uint32_t value, DataPointCode code);
+ void processLimits(uint16_t *cacheValue, uint16_t value, DataPointCode code, boolean maximum);
+ void processLimits(int16_t *cacheValue, int16_t value, DataPointCode code, boolean maximum);
+ void reset();
+
+ char inBuffer[CFG_WIFI_BUFFER_SIZE]; //storage for incoming data
+ byte outBuffer[CFG_WIFI_BUFFER_SIZE]; // buffer to compose and send data to ESP32
+ uint16_t inPos, outPos; //write position for inBuffer
+ uint16_t dataPointCount; // how many data points were added to outBuffer;
+ String sendBuffer[CFG_SERIAL_SEND_BUFFER_SIZE];
+ int psWritePtr;
+ int psReadPtr;
+ bool didParamLoad;
+ bool connected; // is a client connected via websocket ?
+ uint32_t timeStarted, timeHeartBeat;
+ bool heartBeatEnabled;
+ uint8_t updateCount;
+ static const int DATA_POINT_START = 0xaa;
+};
+
+#endif
diff --git a/WifiIchip2128.cpp b/WifiIchip2128.cpp
new file mode 100644
index 0000000..fa381c4
--- /dev/null
+++ b/WifiIchip2128.cpp
@@ -0,0 +1,704 @@
+/*
+ * ichip_2128.cpp
+ *
+ * Class to interface with the ichip 2128 based wifi adapter we're using on our board
+ *
+ Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
+
+ 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 "WifiIchip2128.h"
+
+/**
+ * \brief Constructor
+ *
+ * Assign serial interface to use for ichip communication
+ *
+ */
+WifiIchip2128::WifiIchip2128() : Wifi()
+{
+ prefsHandler = new PrefHandler(ICHIP2128);
+
+ serialInterface->begin(115200);
+
+ commonName = "WIFI (iChip2128)";
+
+ for (int i = 0; i < CFG_WIFI_NUM_SOCKETS; i++) {
+ socket[i].handle = -1;
+ socket[i].processor = NULL;
+ }
+
+ didParamLoad = didTCPListener = false;
+ tickCounter = watchdogCounter = 0;
+ ibWritePtr = psWritePtr = psReadPtr = 0;
+ socketListenerHandle = 0;
+ lastSendTime = timeStarted = 0;
+ lastSendSocket = NULL;
+ state = IDLE;
+ remainingSocketRead = -1;
+
+ pinMode(CFG_WIFI_RESET, OUTPUT);
+ pinMode(CFG_WIFI_ENABLE, OUTPUT);
+}
+
+/**
+ * \brief Initialization of hardware and parameters
+ *
+ */
+void WifiIchip2128::setup()
+{
+ digitalWrite(CFG_WIFI_RESET, HIGH);
+ digitalWrite(CFG_WIFI_ENABLE, HIGH);
+
+ for (int i = 0; i < CFG_WIFI_NUM_SOCKETS; i++) {
+ socket[i].handle = -1;
+ socket[i].processor = NULL;
+ }
+
+ didParamLoad = didTCPListener = false;
+ tickCounter = watchdogCounter = 0;
+ ibWritePtr = psWritePtr = psReadPtr = 0;
+ socketListenerHandle = 0;
+ lastSendSocket = NULL;
+ remainingSocketRead = -1;
+ lastSendTime = timeStarted = millis();
+ state = IDLE;
+
+ // don't try to re-attach if called from reset() - to avoid warning message
+ if (!tickHandler.isAttached(this, CFG_TICK_INTERVAL_WIFI)) {
+ tickHandler.attach(this, CFG_TICK_INTERVAL_WIFI);
+ }
+
+ ready = true;
+ running = true;
+}
+
+/**
+ * \brief Tear down the device in a safe way.
+ *
+ */
+void WifiIchip2128::tearDown()
+{
+ Device::tearDown();
+ digitalWrite(CFG_WIFI_ENABLE, LOW);
+}
+
+/**
+ * \brief Send a command to ichip
+ *
+ * A version which defaults to IDLE which is what most of the code used to assume.
+ *
+ * \param cmd the command string to be sent
+ */
+void WifiIchip2128::sendCmd(String cmd)
+{
+ sendCmd(cmd, IDLE);
+}
+
+/**
+ * \brief Send a command to ichip.
+ *
+ * A version used if no socket information is required
+ *
+ * \param cmd the command to send (without the preceeding AT+i)
+ * \param cmdstate the command state the ichip is after sending this command
+ */
+void WifiIchip2128::sendCmd(String cmd, ICHIP_COMM_STATE cmdstate)
+{
+ sendCmd(cmd, cmdstate, NULL);
+}
+
+/**
+ * \brief Send a command to ichip.
+ *
+ * The "AT+i" part will be added. If the comm channel is busy it buffers the command
+ *
+ * \param cmd the command to send (without the preceeding AT+i)
+ * \param cmdstate the command state the ichip is after sending this command
+ * \param socket the socket to which the command is related
+ */
+void WifiIchip2128::sendCmd(String cmd, ICHIP_COMM_STATE cmdstate, Socket *socket)
+{
+ //if the comm is tied up, then buffer this parameter for sending later
+ if (state != IDLE) {
+ sendBuffer[psWritePtr].cmd = cmd;
+ sendBuffer[psWritePtr].state = cmdstate;
+ sendBuffer[psWritePtr++].socket = socket;
+ if (psWritePtr >= CFG_SERIAL_SEND_BUFFER_SIZE) {
+ psWritePtr = 0;
+ }
+ if (logger.isDebug()) {
+ logger.debug(this, "Buffer cmd: %s", cmd.c_str());
+ }
+ } else { //otherwise, go ahead and blast away
+ serialInterface->print(ichipCommandPrefix);
+ serialInterface->print(cmd);
+ serialInterface->write(13);
+ state = cmdstate;
+ lastSendSocket = socket;
+ lastSendTime = millis();
+ if (logger.isDebug()) {
+ logger.debug(this, "Send cmd: %s", cmd.c_str());
+ }
+ }
+}
+
+/**
+ * \brief Try to send a buffered command to ichip
+ */
+void WifiIchip2128::sendBufferedCommand()
+{
+ state = IDLE;
+ if (psReadPtr != psWritePtr) {
+ logger.debug(this, "sending buffered command");
+ //if there is a parameter in the buffer to send then do it
+ sendCmd(sendBuffer[psReadPtr].cmd, sendBuffer[psReadPtr].state, sendBuffer[psReadPtr++].socket);
+ if (psReadPtr >= CFG_SERIAL_SEND_BUFFER_SIZE) {
+ psReadPtr = 0;
+ }
+ }
+}
+
+/**
+ * \brief Send data to a specific socket
+ *
+ * \param socket to send data to
+ * \param data to send to client via socket
+ */
+void WifiIchip2128::sendToSocket(Socket *socket, String data)
+{
+ if (data == NULL || data.length() < 1 || socket->handle == -1) {
+ return;
+ }
+ sprintf(buffer, "SSND%%:%i,%i:", socket->handle, data.length());
+ String temp = String(buffer);
+ temp.concat(data);
+ sendCmd(temp, SEND_SOCKET, socket);
+}
+
+/**
+ * \brief Request the delivery of waiting data from active sockets
+ *
+ * Only request if we're not already in midst of it
+ *
+ */
+void WifiIchip2128::requestIncomingSocketData()
+{
+ if (state != GET_SOCKET) {
+ for (int i = 0; i < CFG_WIFI_NUM_SOCKETS; i++) {
+ if (socket[i].handle != -1) {
+ sprintf(buffer, "SRCV:%i,1024", socket[i].handle);
+ sendCmd(buffer, GET_SOCKET, &socket[i]);
+ }
+ }
+ }
+}
+
+/**
+ * \brief Request list of open handles for socket
+ *
+ */
+void WifiIchip2128::requestActiveSocketList()
+{
+ sprintf(buffer, "LSST:%u", socketListenerHandle);
+ sendCmd(buffer, GET_ACTIVE_SOCKETS);
+}
+
+/**
+ * \brief Start up a listening socket (for WebSockets or OBDII devices)
+ *
+ */
+void WifiIchip2128::startSocketListener()
+{
+ sprintf(buffer, "LTCP:2000,%u", CFG_WIFI_NUM_SOCKETS);
+ sendCmd(buffer, START_TCP_LISTENER);
+}
+
+/**
+ * \brief Send update to all active sockets
+ *
+ * The message to be sent is created by the assigned SocketProcessor
+ *
+ */
+void WifiIchip2128::sendSocketUpdate()
+{
+ for (int i = 0; i < CFG_WIFI_NUM_SOCKETS; i++) {
+ if (socket[i].handle != -1 && socket[i].processor != NULL) {
+ String data = socket[i].processor->generateUpdate();
+ sendToSocket(&socket[i], data);
+ }
+ }
+}
+
+/**
+ * \brief Perform regular tasks triggered by a timer
+ *
+ * Query for changed parameters of the config page, socket status
+ * and query for incoming data on sockets
+ *
+ */
+void WifiIchip2128::handleTick()
+{
+ if (!running) { // re-init after a reset
+ setup();
+ return;
+ }
+ if (watchdogCounter++ > 250) { // after 250 * 100ms no reception, reset ichip
+ logger.warn(this, "watchdog: no response from ichip");
+ reset();
+ return;
+ }
+
+ if (socketListenerHandle != 0) {
+ sendSocketUpdate();
+
+ if (tickCounter == 5) {
+ requestActiveSocketList();
+ } else if (tickCounter % 10 == 0) {
+ requestIncomingSocketData();
+ } else if (tickCounter == 25 && state == IDLE) { // check if params have changed, but only if idle so we don't mess-up other incoming data
+ requestNextParam();
+ }
+ } else { // wait a bit for things to settle before doing a thing
+ if (!didParamLoad && millis() > 3000 + timeStarted) {
+ loadParameters();
+ didParamLoad = true;
+ }
+ if (!didTCPListener && millis() > 5000 + timeStarted) {
+ startSocketListener();
+ didTCPListener = true;
+ }
+ }
+
+ if (++tickCounter > 30) {
+ tickCounter = 0;
+ }
+}
+
+/**
+ * \brief Handle a message sent by the DeviceManager
+ *
+ * \param messageType the type of the message
+ * \param message the message to be processed
+ */
+void WifiIchip2128::handleMessage(uint32_t messageType, void* message)
+{
+ Device::handleMessage(messageType, message);
+
+ switch (messageType) {
+ case MSG_SET_PARAM: {
+ char **params = (char **) message;
+ setParam((char *) params[0], (char *) params[1]);
+ break;
+ }
+
+ case MSG_CONFIG_CHANGE:
+ loadParameters();
+ break;
+
+ case MSG_COMMAND:
+ sendCmd((char *) message);
+ process();
+ break;
+
+ case MSG_RESET:
+ factoryDefaults();
+ break;
+
+ case MSG_LOG:
+ char **params = (char **) message;
+ for (int i = 0; i < CFG_WIFI_NUM_SOCKETS; i++) {
+ if (socket[i].handle != -1 && socket[i].processor != NULL) {
+ String data = socket[i].processor->generateLogEntry(params[0], params[1], params[2]);
+ sendToSocket(&socket[i], data);
+ }
+ }
+ break;
+ }
+}
+
+/**
+ * \brief Act on system state changes and send an update to the socket client
+ *
+ * \param oldState the previous system state
+ * \param newState the new system state
+ */
+void WifiIchip2128::handleStateChange(Status::SystemState oldState, Status::SystemState newState)
+{
+ Device::handleStateChange(oldState, newState);
+ sendSocketUpdate();
+
+}
+
+/**
+ * \brief Process serial input waiting from the wifi module.
+ *
+ * The method is called by the main loop
+ */
+void WifiIchip2128::process()
+{
+ int incoming;
+ while (serialInterface->available()) {
+ incoming = serialInterface->read();
+//SerialUSB.print((char)incoming);
+ if (incoming == -1) { //and there is no reason it should be -1
+ return;
+ }
+ if (remainingSocketRead > 0) {
+ remainingSocketRead--;
+ if (state == GET_SOCKET) { // just add the char and ignore nothing (not even CR/LF or 0)
+ incomingBuffer[ibWritePtr++] = (char) incoming;
+ if (remainingSocketRead > 0 && ibWritePtr < CFG_WIFI_BUFFER_SIZE) {
+ continue;
+ }
+ }
+ }
+
+ // in GET_SOCKET mode, check if we need to parse the size info from a SRCV command yet
+ if (state == GET_SOCKET && remainingSocketRead == -1 && ibWritePtr > 2 && (incoming == ':' || incomingBuffer[2] == '0') &&
+ incomingBuffer[0] == 'I' && incomingBuffer[1] == '/' && isdigit(incomingBuffer[2])) {
+ processSocketResponseSize();
+ return;
+ }
+
+ if (incoming == 13 || ibWritePtr > (CFG_WIFI_BUFFER_SIZE - 2) || remainingSocketRead == 0) { // on CR or full buffer, process the line
+ incomingBuffer[ibWritePtr] = 0; //null terminate the string
+ ibWritePtr = 0; //reset the write pointer
+
+ if (logger.isDebug()) {
+ logger.debug(this, "incoming: '%s', state: %d", incomingBuffer, state);
+ }
+
+ //The ichip echoes our commands back at us. The safer option might be to verify that the command
+ //we think we're about to process is really proper by validating the echo here. But, for now
+ //just ignore echoes - except for SSND (socket send, where an error might be added at the end)
+ if (strncmp(incomingBuffer, ichipCommandPrefix.c_str(), 4) != 0) {
+ switch (state) {
+ case GET_PARAM: //reply from an attempt to read changed parameters from ichip
+ processParameterChange(incomingBuffer);
+ break;
+ case SET_PARAM: //reply from sending parameters to the ichip
+ break;
+ case START_TCP_LISTENER: //reply from turning on a listening socket
+ processStartSocketListenerRepsonse();
+ break;
+ case GET_ACTIVE_SOCKETS: //reply from asking for active connections
+ processActiveSocketListResponse();
+ break;
+ case POLL_SOCKET: //reply from asking about state of socket and how much data it has
+ break;
+ case SEND_SOCKET: //reply from sending data over a socket
+ break;
+ case GET_SOCKET: //reply requesting the data pending on a socket
+ processIncomingSocketData();
+ break;
+ case IDLE:
+ default:
+ //logger.info(this, incomingBuffer);
+ break;
+ }
+ } else {
+ // although we ignore all echo's of "AT+i", the "AT+iSSND" has the I/OK or I/ERROR in-line
+ if (strstr(incomingBuffer, "AT+iSSND") != NULL) {
+ processSocketSendResponse();
+ }
+ }
+ // if we got an I/OK or I/ERROR in the reply then the command is done sending data. So, see if there is a buffered cmd to send.
+ if (strstr(incomingBuffer, "I/OK") != NULL) {
+ watchdogCounter = 0; // the ichip responds --> it's alive
+ sendBufferedCommand();
+ }
+ if (strstr(incomingBuffer, ichipErrorString.c_str()) != NULL) {
+ logger.warn("ichip responded with error: '%s', state %d", incomingBuffer, state);
+ sendBufferedCommand();
+ }
+ return; // before processing the next line, return to the process() to allow other devices to process.
+ } else { // add more characters
+ if (incoming != 10) { // don't add a LF character
+ incomingBuffer[ibWritePtr++] = (char) incoming;
+ }
+ }
+ }
+ if (millis() > lastSendTime + 1000) {
+ logger.debug(this, "response timeout");
+ lastSendTime = millis();
+ sendBufferedCommand(); //something went wrong so reset state
+ }
+}
+
+/**
+ * \brief Handle the response of a request to start the socket listener
+ *
+ */
+void WifiIchip2128::processStartSocketListenerRepsonse()
+{
+ //reply hopefully has the listening socket handle
+ if (strcmp(incomingBuffer, ichipErrorString.c_str())) {
+ socketListenerHandle = atoi(&incomingBuffer[2]);
+ if (socketListenerHandle < 10 || socketListenerHandle > 11) {
+ socketListenerHandle = 0;
+ }
+ if (logger.isDebug()) {
+ logger.debug(this, "socket listener handle: %i", socketListenerHandle);
+ }
+ }
+ sendBufferedCommand();
+}
+
+/**
+ * \brief Handle the response of a request to get the list of active sockets
+ *
+ */
+void WifiIchip2128::processActiveSocketListResponse()
+{
+ if (strcmp(incomingBuffer, ichipErrorString.c_str())) {
+ if (strncmp(incomingBuffer, "I/(", 3) == 0) {
+ socket[0].handle = atoi(strtok(&incomingBuffer[3], ","));
+ for (int i = 1; i < CFG_WIFI_NUM_SOCKETS; i++) {
+ socket[i].handle = atoi(strtok(NULL, ","));
+ }
+ }
+ } else {
+ logger.warn(this, "could not retrieve list of active sockets, closing all open sockets");
+ closeAllSockets();
+ }
+ // as the reply only contains "I/(000,-1,-1,-1)" it won't be recognized in process() as "I/OK" or "I/ERROR",
+ // to proceed with processing the buffer, we need to call it here.
+ sendBufferedCommand();
+}
+
+/**
+ * \brief Extract the size of the socket response data
+ *
+ */
+void WifiIchip2128::processSocketResponseSize()
+{
+ incomingBuffer[ibWritePtr] = 0; //null terminate the string
+ ibWritePtr = 0; //reset the write pointer
+ remainingSocketRead = constrain(atoi(&incomingBuffer[2]), 0, 1024);
+ if(remainingSocketRead == 0) {
+ remainingSocketRead--;
+ sendBufferedCommand();
+ } else {
+ logger.debug(this, "processing remaining socket read: %d", remainingSocketRead);
+ }
+}
+
+/**
+ * \brief Process incoming data from a socket
+ *
+ * The data is forwarded to the socket's assigned SocketProcessor. The processor prepares a
+ * response which is sent back to the client via the socket.
+ *
+ */
+void WifiIchip2128::processIncomingSocketData()
+{
+ logger.debug(this, "processing incoming socket data");
+
+ if (strstr(incomingBuffer, ichipErrorString.c_str()) != NULL) {
+ logger.warn(this, "could not retrieve data from socket %d, closing socket", lastSendSocket->handle);
+ closeSocket(lastSendSocket);
+ }
+
+ if (lastSendSocket != NULL) {
+ if (lastSendSocket->processor == NULL) {
+ if (strstr(incomingBuffer, "HTTP") != NULL) {
+ logger.info("connecting to web-socket client");
+ lastSendSocket->processor = new WebSocket();
+ } else {
+ logger.info("connecting to ELM327 device");
+ lastSendSocket->processor = new ELM327Processor();
+ }
+ }
+
+ String data = lastSendSocket->processor->processInput(incomingBuffer);
+ if (data.length() > 0) {
+ if (data.equals(disconnect)) { // do we have to disconnect ?
+ closeSocket(lastSendSocket);
+ } else {
+ sendToSocket(lastSendSocket, data);
+ }
+ }
+ }
+
+ if (remainingSocketRead == 0) {
+ remainingSocketRead = -1;
+ sendBufferedCommand();
+ }
+}
+
+/**
+ * \brief Handle the response of a socket send command
+ *
+ * An eventual error is not sent in a separate line but in the same as the echo
+ * of the SSND. It can happen e.g. when the socket was closed by the client
+ * (e.g. "AT+iSSND%:000,24:I/ERROR (203)")
+ *
+ */
+void WifiIchip2128::processSocketSendResponse()
+{
+ if (strstr(incomingBuffer, ichipErrorString.c_str()) != NULL &&
+ strstr(incomingBuffer, "(203)") != NULL) {
+ logger.info(this, "connection closed by remote client (%s), closing socket", incomingBuffer);
+ closeSocket(lastSendSocket);
+ }
+}
+
+/**
+ * \brief Close all open socket
+ *
+ */
+void WifiIchip2128::closeAllSockets()
+{
+ for (int c = 0; c < CFG_WIFI_NUM_SOCKETS; c++) {
+ closeSocket(&socket[c]);
+ }
+}
+
+/**
+ * \brief Close a specific socket
+ *
+ * \param socket to close
+ */
+void WifiIchip2128::closeSocket(Socket *socket)
+{
+ if (socket->handle != -1) {
+ logger.debug(this, "closing socket %i", socket->handle);
+ sprintf(buffer, "!SCLS:%i", socket->handle);
+ sendCmd(buffer, SEND_SOCKET, socket);
+ }
+ socket->handle = -1;
+ socket->processor = NULL;
+}
+
+/**
+ * \brief Determine if a parameter has been changed
+ *
+ * The result will be processed in process() -> processParameterChange()
+ *
+ */
+void WifiIchip2128::requestNextParam()
+{
+ sendCmd("WNXT", GET_PARAM); //send command to get next changed parameter
+}
+
+/**
+ * \brief Retrieve the value of a parameter
+ *
+ * \param paramName the name of the parameter
+ */
+void WifiIchip2128::requestParamValue(String paramName)
+{
+ sendCmd(paramName + "?", GET_PARAM);
+}
+
+/**
+ * \brief Set a parameter to the given string value
+ *
+ * \param paramName the name of the parameter
+ * \param value the value to set
+ */
+void WifiIchip2128::setParam(String paramName, String value)
+{
+ sendCmd(paramName + "=\"" + value + "\"", SET_PARAM);
+}
+
+/**
+ * \brief Reset the ichip to overcome a crash
+ *
+ */
+void WifiIchip2128::reset()
+{
+ logger.info(this, "resetting the ichip");
+
+ // cycle reset pin (next tick() will activate it again
+ digitalWrite(CFG_WIFI_RESET, LOW);
+ running = false;
+ ready = false;
+}
+
+/**
+ * \brief Reset to ichip to factory defaults and set-up GEVCU network
+ *
+ */
+void WifiIchip2128::factoryDefaults() {
+ logger.info(this, "resetting to factory defaults");
+ tickHandler.detach(this); // stop other activity
+ psReadPtr = psWritePtr = 0; // purge send buffer
+
+ delay(1000);
+ sendCmd("", IDLE); // just in case something was still on the line
+ delay(1000);
+ sendCmd("FD", IDLE);
+ delay(3000);
+ sendCmd("HIF=1", IDLE);//Set for RS-232 serial.
+ delay(1000);
+ // set-up specific ad-hoc network
+ sendCmd("BDRA", IDLE);
+ delay(1000);
+ sendCmd("WLCH=1", IDLE);//use whichever channel an AP wants to use
+ delay(1000);
+ sendCmd("WLSI=!GEVCU", IDLE);//set SSID
+ delay(1000);
+ sendCmd("DIP=192.168.3.10", IDLE);//enable searching for a proper IP via DHCP
+ delay(1000);
+ sendCmd("DPSZ=10", IDLE);// enable DHCP server for 10 IPs
+ delay(1000);
+#ifdef CFG_WIFI_WPA2
+ sendCmd("WST0=4", IDLE);// enable WPA2-PSK security
+ delay(1000);
+ sendCmd("WSEC=1", IDLE);// use WPA2-AES protocol
+ delay(1000);
+ sendCmd("WPP0=verysecret", IDLE);// WPA2 password
+ delay(25000); // it really takes that long to calculate the key !!
+#endif
+ sendCmd("RPG=*", IDLE);// allow everybody to update the params - no PW-Authentication
+ delay(1000);
+ sendCmd("WPWD=*", IDLE);// no password required to update params
+ delay(1000);
+ sendCmd("AWS=3", IDLE);//turn on web server for 3 concurrent connections
+ delay(1000);
+ sendCmd("DOWN", IDLE);//cause a reset to allow it to come up with the settings
+ delay(5000);// a 5 second delay is required for the chip to come back up ! Otherwise commands will be lost
+
+ tickHandler.attach(this, CFG_TICK_INTERVAL_WIFI);
+}
+
+/**
+ * \brief Get the device type
+ *
+ * \return the type of the device
+ */
+DeviceType WifiIchip2128::getType()
+{
+ return DEVICE_WIFI;
+}
+
+/**
+ * \brief Get the device ID
+ *
+ * \return the ID of the device
+ */
+DeviceId WifiIchip2128::getId()
+{
+ return (ICHIP2128);
+}
diff --git a/ichip_2128.h b/WifiIchip2128.h
similarity index 54%
rename from ichip_2128.h
rename to WifiIchip2128.h
index c5d768e..a0fac0a 100644
--- a/ichip_2128.h
+++ b/WifiIchip2128.h
@@ -12,7 +12,7 @@
* If none of those networks can be found then the device will automatically try to form an
* adhoc network with the 4th entry which is dedicated to that purpose.
* All commands to the wifi start with "AT+i" and end with CR (ascii 13)
- *
+ *
* Commands:
* RP11 - get list of access points in range
* RP7 - Status report (bit 10 if remote has changed a param)
@@ -42,13 +42,13 @@
* WSIx - x=0-9 = set SSIDs to associate with
* WPPx - x=0-9 WPA pass phrases
* WKYx - x=0-9 WEP keys
- * WSTx - x=0-9 security type = (0=none, 1=wep64, 2=WEP128,3=WPA/TKIP 4=WPA2
- *
- *
+ * WSTx - x=0-9 security type = (0=none, 1=wep64, 2=WEP128,3=WPA/TKIP 4=WPA2
+ *
+ *
* Web Parameters getting/setting
- * = set
- * ? get
- *
+ * = set
+ * ? get
+ *
Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
@@ -78,128 +78,89 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
#include
#include "config.h"
-#include "constants.h"
#include "DeviceManager.h"
-#include "PotThrottle.h"
#include "Sys_Messages.h"
#include "DeviceTypes.h"
#include "ELM327Processor.h"
-//#include "sys_io.h"
+#include "WebSocket.h"
+#include "SocketProcessor.h"
+#include "Wifi.h"
+static const String ichipErrorString = "I/ERROR";
+static const String disconnect = "_DISCONNECT_";
-extern PrefHandler *sysPrefs;
enum ICHIP_COMM_STATE {IDLE, GET_PARAM, SET_PARAM, START_TCP_LISTENER, GET_ACTIVE_SOCKETS, POLL_SOCKET, SEND_SOCKET, GET_SOCKET};
-/*
- * The extended configuration class with additional parameters for ichip WLAN
- */
-class WifiConfiguration : public DeviceConfiguration {
-public:
-};
-
-/**
- * Cache of param values to avoid sending an update unless changed
- */
-struct ParamCache {
- uint32_t timeRunning;
- int16_t torqueRequested;
- int16_t torqueActual;
- int16_t throttle;
- int16_t brake;
- bool brakeNotAvailable;
- int16_t speedRequested;
- int16_t speedActual;
- MotorController::PowerMode powerMode;
- int16_t dcVoltage;
- int16_t dcCurrent;
- int16_t acCurrent;
- int16_t nominalVolt;
- int16_t kiloWattHours;
- uint32_t bitfield1;
- uint32_t bitfield2;
- uint32_t bitfield3;
- uint32_t bitfield4;
- bool running;
- bool faulted;
- bool warning;
- MotorController::Gears gear;
- int16_t tempMotor;
- int16_t tempInverter;
- int16_t tempSystem;
- int16_t mechPower;
- int16_t prechargeR;
- int8_t prechargeRelay;
- int8_t mainContactorRelay;
- int8_t coolFan;
- int8_t coolOn;
- int8_t coolOff;
- int8_t brakeLight;
- int8_t revLight;
- int8_t enableIn;
- int8_t reverseIn;
+struct Socket {
+ int8_t handle;
+ SocketProcessor *processor;
};
struct SendBuff {
- String cmd;
- ICHIP_COMM_STATE state;
+ String cmd;
+ ICHIP_COMM_STATE state;
+ Socket *socket;
};
-class ICHIPWIFI : public Device {
- public:
-
- ICHIPWIFI();
- ICHIPWIFI(USARTClass *which);
+class WifiIchip2128 : public Wifi
+{
+public:
+ WifiIchip2128();
+ WifiIchip2128(USARTClass *which);
void setup(); //initialization on start up
+ void tearDown();
void handleTick(); //periodic processes
void handleMessage(uint32_t messageType, void* message);
- DeviceType getType();
+ void handleStateChange(Status::SystemState, Status::SystemState);
+ DeviceType getType();
DeviceId getId();
- void loop();
- char *getTimeRunning();
-
-
- void loadConfiguration();
- void saveConfiguration();
- void loadParameters();
-
-
- private:
- ELM327Processor *elmProc;
- USARTClass* serialInterface; //Allows for retargetting which serial port we use
- char incomingBuffer[128]; //storage for one incoming line
- int ibWritePtr; //write position into above buffer
- SendBuff sendingBuffer[64];
- int psWritePtr;
- int psReadPtr;
- int tickCounter;
- int currReply;
- char buffer[30]; // a buffer for various string conversions
- ParamCache paramCache;
- ICHIP_COMM_STATE state;
- bool didParamLoad;
- bool didTCPListener;
- int listeningSocket;
- int activeSockets[4]; //support for four sockets. Lowest byte is socket #, next byte is size of data waiting in that socket
- uint32_t lastSentTime;
- String lastSentCmd;
- ICHIP_COMM_STATE lastSentState;
-
- void getNextParam(); //get next changed parameter
- void getParamById(String paramName); //try to retrieve the value of the given parameter
- void setParam(String paramName, String value); //set the given parameter with the given string
- void setParam(String paramName, int32_t value);
- void setParam(String paramName, int16_t value);
- void setParam(String paramName, uint32_t value);
- void setParam(String paramName, uint16_t value);
- void setParam(String paramName, uint8_t value);
- void setParam(String paramName, float value, int precision);
- void sendCmd(String cmd);
- void sendCmd(String cmd, ICHIP_COMM_STATE cmdstate);
- void sendToSocket(int socket, String data);
- void processParameterChange(char *response);
+ void process();
-
+private:
+ void requestNextParam(); //get next changed parameter
+ void requestParamValue(String paramName); //try to retrieve the value of the given parameter
+ void setParam(String paramName, String value); //set the given parameter with the given string
+ void sendCmd(String cmd);
+ void sendCmd(String cmd, ICHIP_COMM_STATE cmdstate);
+ void sendCmd(String cmd, ICHIP_COMM_STATE cmdstate, Socket *socket);
+ void sendBufferedCommand();
+ void sendToSocket(Socket *socket, String data);
+ void sendSocketUpdate();
+ void processStartSocketListenerRepsonse();
+ void processActiveSocketListResponse();
+ void processIncomingSocketData();
+ void processSocketSendResponse();
+ void closeAllSockets();
+ void closeSocket(Socket *socket);
+
+ void reset();
+ void factoryDefaults();
+ void processSocketResponseSize();
+ void requestIncomingSocketData();
+ void requestActiveSocketList();
+ void startSocketListener();
+
+ char incomingBuffer[CFG_WIFI_BUFFER_SIZE]; //storage for one incoming line
+ int ibWritePtr; //write position into above buffer
+ SendBuff sendBuffer[CFG_SERIAL_SEND_BUFFER_SIZE];
+ int psWritePtr;
+ int psReadPtr;
+ int tickCounter;
+ char buffer[30]; // a buffer for various string conversions
+ ICHIP_COMM_STATE state;
+ bool didParamLoad;
+ bool didTCPListener;
+ int socketListenerHandle;
+ uint32_t lastSendTime;
+ uint32_t timeStarted;
+ Socket *lastSendSocket;
+ int remainingSocketRead;
+ uint8_t watchdogCounter; // a counter to find out if ichip has crashed
+ Socket socket[CFG_WIFI_NUM_SOCKETS];
+
+ const String disconnect = "_DISCONNECT_";
+ const String ichipCommandPrefix = "AT+i";
};
#endif
diff --git a/config.h b/config.h
index f10926c..a560743 100644
--- a/config.h
+++ b/config.h
@@ -27,16 +27,18 @@ 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.
- * Author: Michael Neuweiler
*/
#ifndef CONFIG_H_
#define CONFIG_H_
-#include
+#define CFG_BUILD_NUM 1071 //increment this every time a git commit is done.
+#define CFG_VERSION "GEVCU 2021-08-07"
+#define CFG_DEFAULT_LOGLEVEL Logger::Info
-#define CFG_BUILD_NUM 1051 //increment this every time a git commit is done.
-#define CFG_VERSION "GEVCU 2014-09-16"
+//define this to add in latency and efficiency calculations. Comment it out for builds you're going to
+//use in an actual car. No need to waste cycles for 99% of everyone using the code.
+//#define CFG_EFFICIENCY_CALCS
/*
@@ -45,11 +47,6 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
#define CFG_SERIAL_SPEED 115200
//#define SerialUSB Serial // re-route serial-usb output to programming port ;) comment if output should go to std usb
-
-//The defines that used to be here to configure devices are gone now.
-//The EEPROM stores which devices to bring up at start up and all
-//devices are programmed into the firware at the same time.
-
/*
* TIMER INTERVALS
*
@@ -57,84 +54,59 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
* try to use the same numbers for several devices because then they will share
* the same timer (out of a limited number of 9 timers).
*/
-#define CFG_TICK_INTERVAL_HEARTBEAT 2000000
-#define CFG_TICK_INTERVAL_POT_THROTTLE 40000
-#define CFG_TICK_INTERVAL_CAN_THROTTLE 40000
-#define CFG_TICK_INTERVAL_MOTOR_CONTROLLER 40000
-#define CFG_TICK_INTERVAL_MOTOR_CONTROLLER_DMOC 40000
-#define CFG_TICK_INTERVAL_MOTOR_CONTROLLER_CODAUQM 10000
-#define CFG_TICK_INTERVAL_MOTOR_CONTROLLER_BRUSA 20000
-#define CFG_TICK_INTERVAL_MEM_CACHE 40000
-#define CFG_TICK_INTERVAL_BMS_THINK 500000
-#define CFG_TICK_INTERVAL_WIFI 200000
-
+#define CFG_TICK_INTERVAL_HEARTBEAT 2000000
+#define CFG_TICK_INTERVAL_POT_THROTTLE 100000
+#define CFG_TICK_INTERVAL_CAN_THROTTLE 100000
+#define CFG_TICK_INTERVAL_CAN_OBD2 200000
+#define CFG_TICK_INTERVAL_MOTOR_CONTROLLER_DMOC 40000
+#define CFG_TICK_INTERVAL_MOTOR_CONTROLLER_CODAUQM 10000
+#define CFG_TICK_INTERVAL_MOTOR_CONTROLLER_BRUSA 30000
+#define CFG_TICK_INTERVAL_MEM_CACHE 40000
+#define CFG_TICK_INTERVAL_STATUS 40000
+#define CFG_TICK_INTERVAL_BMS_THINK 500000
+#define CFG_TICK_INTERVAL_BMS_ORION 500000
+#define CFG_TICK_INTERVAL_DCDC_BSC6 100000
+#define CFG_TICK_INTERVAL_CHARGE_NLG5 100000
+#define CFG_TICK_INTERVAL_WIFI 100000
+#define CFG_TICK_INTERVAL_SYSTEM_IO 200000
+#define CFG_TICK_INTERVAL_CAN_IO 200000
/*
* CAN BUS CONFIGURATION
*/
#define CFG_CAN0_SPEED CAN_BPS_500K // specify the speed of the CAN0 bus (EV)
#define CFG_CAN1_SPEED CAN_BPS_500K // specify the speed of the CAN1 bus (Car)
-#define CFG_CAN0_NUM_RX_MAILBOXES 7 // amount of CAN bus receive mailboxes for CAN0
-#define CFG_CAN1_NUM_RX_MAILBOXES 7 // amount of CAN bus receive mailboxes for CAN1
-#define CFG_CANTHROTTLE_MAX_NUM_LOST_MSG 3 // maximum number of lost messages allowed
+#define CFG_CAN0_NUM_TX_MAILBOXES 2 // how many of 8 mailboxes are used for TX for CAN0, rest is used for RX
+#define CFG_CAN1_NUM_TX_MAILBOXES 3 // how many of 8 mailboxes are used for TX for CAN1, rest is used for RX
+#define CFG_CANTHROTTLE_MAX_NUM_LOST_MSG 5 // maximum number of lost messages allowed (max 255)
+#define CFG_MOTORCTRL_MAX_NUM_LOST_MSG 20 // maximum number of ticks the controller may not send messages (max 255)
/*
* MISCELLANEOUS
*
*/
#define CFG_THROTTLE_TOLERANCE 150 //the max that things can go over or under the min/max without fault - 1/10% each #
-
+#define CFG_TORQUE_BRAKE_LIGHT_ON -500 // torque in 0.1Nm where brake light should be turned on - to prevent being kissed from behind
+#define CFG_BRAKE_HOLD_MAX_TIME 5000 // max amount of ms to apply the brake hold functionality
+#define CFG_PRE_CHARGE_RELAY_DELAY 200 // a delay to allow relays to (de-)activate before proceeding with next steps
+#define CFG_PRE_CHARGE_START 1000 // delay for the pre-charge process to start - ensuring other deivces become available
+#define CFG_THREE_CONTACTOR_PRECHARGE // do we use three contactors instead of two for pre-charge cycle ?
+#define CFG_NO_TEMPERATURE_DATA 9999 // temperature used to indicate that no external temp sensor is connected
+#define CFG_MIN_BATTERY_CHARGE_TEMPERATURE 5 // GEVCU won't start the battery charging process if the battery temp is below 5 deg C
+#define CFG_WIFI_WPA2 // enable WPA2 encryption for ad-hoc wifi network at wifi reset (via command 'w'), comment line to disable
+#define CFG_CAN_TEMPERATURE_OFFSET 50 // offset of temperatures reported via CAN bus - make sure GEVCU extension uses the same value!
+#define CFG_ADC_GAIN 1024 // ADC gain centered at 1024 being 1 to 1 gain, thus 512 is 0.5 gain, 2048 is double, etc
+#define CFG_ADC_OFFSET 0 // ADC offset from zero - ADC reads 12 bit so the offset will be [0,4095] - Offset is subtracted from read ADC value
+#define CFG_THROTTLE_MAX_ERROR 150 //tenths of percentage allowable deviation between pedals
+#define CFG_WEBSOCKET_MAX_TIME 25 // maximum processing time when assembling websocket message (in ms) - prevents interruptions when sending messages to controller
+#define CFG_CHARGED_SHUTDOWN_TIME 600000 // ms after status changed to charged when shutting-down the system
/*
* HARD CODED PARAMETERS
*
* If USE_HARD_CODED is defined or the checksum of the parameters stored in EEPROM,
- * the parameter values defined here are used instead of those stored in the EEPROM.
*/
//#define USE_HARD_CODED
-#define ThrottleNumPots 1 //# of pots to use by default
-#define ThrottleADC1 0 //Which pin to use
-#define ThrottleADC2 1 //Which pin to use
-#define ThrottleSubtype 1 //subtype 1 is a standard linear pot throttle
-#define ThrottleRegenMinValue 270 //where does Regen stop (1/10 of percent)
-#define ThrottleRegenMaxValue 30 //where Regen is at maximum (1/10 of percent)
-#define ThrottleFwdValue 300 //where does forward motion start
-#define ThrottleMapValue 750 //Where is the 1/2 way point for throttle
-#define ThrottleMinRegenValue 0 //how many percent of full power to use at minimal regen
-#define ThrottleMaxRegenValue 50 //how many percent of full power to use at maximum regen
-#define ThrottleCreepValue 0 //how many percent of full power to use at creep
-#define ThrottleMaxErrValue 150 //tenths of percentage allowable deviation between pedals
-#define Throttle1MinValue 95 //Value ADC reads when pedal is up
-#define Throttle1MaxValue 3150 //Value ADC reads when pedal fully depressed
-#define Throttle2MinValue 0 //Value ADC reads when pedal is up
-#define Throttle2MaxValue 0 //Value ADC reads when pedal fully depressed
-#define BrakeMinValue 100 //Value ADC reads when brake is not pressed
-#define BrakeMaxValue 3200 //Value ADC reads when brake is pushed all of the way down
-#define BrakeMinRegenValue 0 //percent of full power to use for brake regen (min)
-#define BrakeMaxRegenValue 50 //percent of full power to use for brake regen (max)
-#define BrakeADC 2 //which ADC pin to use
-
-
-#define MaxTorqueValue 3000 //in tenths of a Nm
-#define MaxRPMValue 6000 //DMOC will ignore this but we can use it ourselves for limiting
-#define RPMSlewRateValue 10000 // rpm/sec the requested speed should change (speed mode)
-#define TorqueSlewRateValue 6000 // 0.1Nm/sec the requested torque output should change (torque mode)
-#define KilowattHrs 11000 //not currently used
-#define PrechargeR 3000 //millliseconds precharge
-#define NominalVolt 3300 //a reasonable figure for a lithium cell pack driving the DMOC (in tenths of a volt)
-#define PrechargeRelay 4 //third output
-#define MainContactorRelay 5 //fourth output
-#define ReversePercent 50
-#define CoolFan 255 //output to use for cooling fan
-#define CoolOn 40 //temperature (in C) to turn on cooling fan
-#define BrakeLight 255 //temperature to turn it off
-#define CoolOff 35 //temperature to turn it off
-#define RevLight 255 //temperature to turn it off
-#define EnableIn 255//temperature to turn it off
-#define ReverseIn 255 //temperature to turn it off
-#define MaxRegenWatts 40000 //in actual watts, there is no scale here
-#define MaxAccelWatts 150000
-
/*
* ARRAY SIZE
@@ -143,20 +115,33 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
* These values should normally not be changed.
*/
#define CFG_DEV_MGR_MAX_DEVICES 20 // the maximum number of devices supported by the DeviceManager
-#define CFG_CAN_NUM_OBSERVERS 5 // maximum number of device subscriptions per CAN bus
-#define CFG_TIMER_NUM_OBSERVERS 9 // the maximum number of supported observers per timer
-#define CFG_TIMER_USE_QUEUING // if defined, TickHandler uses a queuing buffer instead of direct calls from interrupts
-#define CFG_TIMER_BUFFER_SIZE 100 // the size of the queuing buffer for TickHandler
+#define CFG_CAN_NUM_OBSERVERS 10 // maximum number of device subscriptions per CAN bus
+#define CFG_TIMER_NUM_OBSERVERS 9 // the maximum number of supported observers per timer
+#define CFG_TIMER_BUFFER_SIZE 100 // the size of the queuing buffer for TickHandler
+#define CFG_SERIAL_SEND_BUFFER_SIZE 140
#define CFG_FAULT_HISTORY_SIZE 50 //number of faults to store in eeprom. A circular buffer so the last 50 faults are always stored.
+#define CFG_WEBSOCKET_BUFFER_SIZE 50 // number of characters an incoming socket frame may contain
+#define CFG_WIFI_NUM_SOCKETS 4 // max number of websocket connections
+#define CFG_WIFI_BUFFER_SIZE 1025 // size of buffer for incoming data from wifi
+#define LOG_BUFFER_SIZE 120 // size of log output messages
+#define CFG_LOG_REPEAT_MSG_TIME 10000 // ms while a repeated message is suppressed to be sent to the wifi
+#define CFG_CRUISE_SPEED_BUFFER_SIZE 10 // size of the buffer for actual speed when using cruise buffer
+#define CFG_CRUISE_BUTTON_LONG_PRESS 1000 // ms after which a button press is considered a long press (for plus/minus)
+#define CFG_CRUISE_SIZE_SPEED_SET 8 // max number of speed set entries (cruise speed buttons in dashboard)
/*
* PIN ASSIGNMENT
*/
-#define CFG_THROTTLE_NONE 255
-#define BLINK_LED 73 //13 is L, 73 is TX, 72 is RX
+#define CFG_OUTPUT_NONE 255
+#define CFG_IO_BLINK_LED 13 // 13 is L, 73 is TX, 72 is RX
+#define CFG_EEPROM_WRITE_PROTECT 19 // pin used to control the write-enable signal for the eeprom, (19=GEVCU >=3, 18=GEVCU 2.x)
+#define CFG_WIFI_RESET 18 // pin to reset wifi chip (18=GEVCU >=3, 17=GEVCU 2)
+#define CFG_WIFI_ENABLE 42 // pin used to enable wifi chip
+
-#define NUM_ANALOG 4
-#define NUM_DIGITAL 4
-#define NUM_OUTPUT 8
+#define CFG_NUMBER_ANALOG_INPUTS 4
+#define CFG_NUMBER_DIGITAL_INPUTS 4
+#define CFG_NUMBER_DIGITAL_OUTPUTS 8
+#define CFG_NUMBER_BATTERY_TEMPERATURE_SENSORS 6 // the maximum supported external temperature sensors for battery
#endif /* CONFIG_H_ */
diff --git a/constants.h b/constants.h
deleted file mode 100644
index 030d5be..0000000
--- a/constants.h
+++ /dev/null
@@ -1,107 +0,0 @@
-/*
- * constants.h
- *
- * Defines the global / application wide constants
- *
-
- Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
-
- 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.
- * Author: Michael Neuweiler
- */
-
-#ifndef CONSTANTS_H_
-#define CONSTANTS_H_
-
-namespace Constants {
- // misc
- static const char* trueStr = "true";
- static const char* falseStr = "false";
- static const char* notAvailable = "n/a";
- static const char* ichipCommandPrefix = "AT+i";
- static const char* ichipErrorString = "I/ERROR";
-
- // configuration
-
- static const char* numThrottlePots = "numThrottlePots";
- static const char* throttleSubType = "throttleSubType";
- static const char* throttleMin1 = "throttleMin1";
- static const char* throttleMin2 = "throttleMin2";
- static const char* throttleMax1 = "throttleMax1";
- static const char* throttleMax2 = "throttleMax2";
- static const char* throttleRegenMax = "throttleRegenMax";
- static const char* throttleRegenMin = "throttleRegenMin";
- static const char* throttleFwd = "throttleFwd";
- static const char* throttleMap = "throttleMap";
- static const char* throttleMinRegen = "throttleMinRegen";
- static const char* throttleMaxRegen = "throttleMaxRegen";
- static const char* throttleCreep = "throttleCreep";
- static const char* brakeMin = "brakeMin";
- static const char* brakeMax = "brakeMax";
- static const char* brakeMinRegen = "brakeMinRegen";
- static const char* brakeMaxRegen = "brakeMaxRegen";
- static const char* brakeLight = "brakeLight";
- static const char* revLight = "revLight";
- static const char* enableIn = "enableIn";
- static const char* reverseIn = "reverseIn";
-
- static const char* speedMax = "speedMax";
- static const char* torqueMax = "torqueMax";
- static const char* logLevel = "logLevel";
-
- // status
- static const char* timeRunning = "timeRunning";
- static const char* torqueRequested = "torqueRequested";
- static const char* torqueActual = "torqueActual";
- static const char* throttle = "throttle";
- static const char* brake = "brake";
- static const char* motorMode = "motorMode";
- static const char* speedRequested = "speedRequested";
- static const char* speedActual = "speedActual";
- static const char* dcVoltage = "dcVoltage";
- static const char* nominalVolt = "nominalVolt";
- static const char* dcCurrent = "dcCurrent";
- static const char* acCurrent = "acCurrent";
- static const char* kiloWattHours = "kiloWattHours";
- static const char* bitfield1 = "bitfield1";
- static const char* bitfield2 = "bitfield2";
- static const char* bitfield3 = "bitfield3";
- static const char* bitfield4 = "bitfield4";
- static const char* running = "running";
- static const char* faulted = "faulted";
- static const char* warning = "warning";
- static const char* gear = "gear";
- static const char* tempMotor = "tempMotor";
- static const char* tempInverter = "tempInverter";
- static const char* tempSystem = "tempSystem";
- static const char* mechPower = "mechPower";
- static const char* prechargeR = "prechargeR";
- static const char* prechargeRelay = "prechargeRelay";
- static const char* mainContactorRelay = "mainContactorRelay";
- static const char* coolFan = "coolFan";
- static const char* coolOn = "coolOn";
- static const char* coolOff = "coolOff";
- static const char* validChecksum = "Valid checksum, using stored config values";
- static const char* invalidChecksum = "Invalid checksum, using hard coded config values";
- static const char* valueOutOfRange = "value out of range: %l";
- static const char* normalOperation = "normal operation restored";
-}
-
-#endif /* CONSTANTS_H_ */
diff --git a/DMOC.txt b/docs/DMOC.txt
similarity index 100%
rename from DMOC.txt
rename to docs/DMOC.txt
diff --git a/docs/Design Drawings.vsd b/docs/Design Drawings.vsd
index 5828bf1..521f20c 100644
Binary files a/docs/Design Drawings.vsd and b/docs/Design Drawings.vsd differ
diff --git a/docs/GEVCU CAN Spec 0.2.xlsx b/docs/GEVCU CAN Spec 0.2.xlsx
new file mode 100644
index 0000000..eea1ad4
Binary files /dev/null and b/docs/GEVCU CAN Spec 0.2.xlsx differ
diff --git a/docs/GEVCU pinout.txt b/docs/GEVCU pinout.txt
index 23f0cc1..695fdf6 100644
--- a/docs/GEVCU pinout.txt
+++ b/docs/GEVCU pinout.txt
@@ -1,17 +1,81 @@
-Pin 1 - +12V Input
-Pin 3 - +12V output for first digital input
-Pin 7 - EXT GND connection to chassis ground / Battery - (in my case)
-Pins 9 & 10 - First canbus
-Pin 19 - Gnd connection for first and second analog inputs (Throttle)
-Pin 20 - First analog input (Throttle)
-Pin 21 - Second analog input (Throttle)
-Pin 22 - Third analog input (brake / testing input for me)
-Pin 23 - Fourth analog input (test pot on my wires)
-Pin 24 - +5V power for first and second analog inputs (Throttle)
-Pin 26 - +5V power for third and fourth analog inputs (test pots for me,
-probably brake transducer for you)
-Pin 30 - Gnd connection for third and fourth analog inputs (Brake / Testing)
-Pin 32 - First digital input. Tied to pin 3 above through a switch
+Pin Assignments
+===============
-I used a gnd at pin 19 for one of the gnds. It really doesn't matter
-which one you use. All four (19,29,30,31) are equivalent.
+Pin | GEVCU 2 | GEVCU 4 | GEVCU 5 |
+-----+-------------------------+-------------------------+-------------------------+
+ 1 | +12V In | +12V In | |
+ 2 | +12V Out (regulated) | +12V Out (regulated) | |
+ 3 | +12V Out (regulated) | Digital Out 0 | |
+ 4 | +12V Out (regulated) | Digital Out 1 | |
+ 5 | +12V Out (regulated) | Digital Out 2 | |
+ 6 | +12V Out (regulated) | Digital Out 3 | |
+ 7 | EXT GND (Chassis/Batt-) | GND | |
+ 8 | GND (not external GND) | GND | |
+ 9 | CAN 0 HI | CAN 0 HI | |
+ 10 | CAN 0 LO | CAN 0 LO | |
+ 11 | CAN 1 HI | CAN 1 HI | |
+ 12 | CAN 1 LO | CAN 1 LO | |
+ 13 | EXT GND | GND | |
+ 14 | EXT GND | GND | |
+ 15 | Digital Out 0 | Digital Out 4 | |
+ 16 | Digital Out 1 | Digital Out 5 | |
+ 17 | Digital Out 2 | Digital Out 6 | |
+ 18 | Digital Out 3 | Digital Out 7 | |
+ 19 | GND | GND | |
+ 20 | Analog In 0 | Analog In 0 | |
+ 21 | Analog In 1 | Analog In 1 | |
+ 22 | Analog In 2 | Analog In 2 | |
+ 23 | Analog In 3 | Analog In 3 | |
+ 24 | +5V Out (isolated) | +5V Out (isolated) | |
+ 25 | +5V Out (isolated) | +5V Out (isolated) | |
+ 26 | +5V Out (isolated) | +5V Out (isolated) | |
+ 27 | +5V Out (isolated) | +5V Out (isolated) | |
+ 28 | +5V Out (isolated) | +5V Out (isolated) | |
+ 29 | GND | GND | |
+ 30 | GND | GND | |
+ 31 | GND | GND | |
+ 32 | Digital In 0 | Digital In 0 | |
+ 33 | Digital In 1 | Digital In 1 | |
+ 34 | Digital In 2 | Digital In 2 | |
+ 35 | Digital In 3 | Digital In 3 | |
+
+
+Ratings
+=======
+
+Parameter | GEVCU 2 | GEVCU 4 | GEVCU 5 |
+---------------------+-------------------------+-------------------------+-------------------------+
+ Supply Voltage | +11 to +14.5 Volt | +xx to +15 Volt | |
+ 12V Out (regulated) | max 1.5 Amp | max 1.5 Amp | |
+ 5V Out (regulated) | max 1 Amp (all pins) | max 1 Amp (all pins) | |
+ Digital Out | max 2 Amp (all pins) | max 1.7 Amp (all pins) | |
+ CAN HI/LO | -27 to 40 Volt | -27 to 40 Volt | |
+ Analog In | 0 to 5 Volt | 0 to 5 Volt | |
+ Digital In | +xx to +15 Volt | +xx to +15 Volt | |
+
+
+Recommended assignments
+=======================
+
+Signal | GEVCU 2 | GEVCU 4 | GEVCU 5 |
+-----------------------------+-----------+-----------+-----------+
+ Supply Voltage / Ignition | Pin 1 | Pin 1 | Pin |
+ Chassis / Battery Negative | Pin 7 | Pin 7 | Pin |
+ Primary / Main Contactor | Pin 16 | Pin 4 | Pin |
+ Pre-Charge Relay | Pin 15 | Pin 3 | Pin |
+ Secondary Contactor (opt) | n/a | Pin 5 | Pin |
+ Enable Signal In | Pin 33 | Pin 33 | Pin |
+ Enable Signal Out (opt) | n/a | Pin 6 | Pin |
+ CAN bus EV components | Pin 9+10 | Pin 9+10 | Pin |
+ CAN bus Car (opt) | Pin 11+12 | Pin 11+12 | Pin |
+ Throttle Signal | Pin 20 | Pin 20 | Pin |
+ Throttle 2nd Signal (opt) | Pin 21 | Pin 21 | Pin |
+ Brake Pressure Transducer | Pin 22 | Pin 22 | Pin |
+ +5V Source Throttle | Pin 24 | Pin 24 | Pin |
+ +5V Source Brake Transduc. | Pin 25 | Pin 25 | Pin |
+ GND Throttle | Pin 29 | Pin 29 | Pin |
+ GND Brake Transducer | Pin 30 | Pin 30 | Pin |
+ Brake Light (switched GND) | Pin 17 | Pin 15 | Pin |
+ Cooling Fan Relay (sw GND) | Pin 18 | Pin 18 | Pin |
+ Reverse Light (switched GND)| n/a | Pin 16 | Pin |
+
\ No newline at end of file
diff --git a/docs/Orion BMS Profile.obms b/docs/Orion BMS Profile.obms
new file mode 100644
index 0000000..8d169a5
--- /dev/null
+++ b/docs/Orion BMS Profile.obms
@@ -0,0 +1,1421 @@
+
+
+
+
diff --git a/gearsandopstates.txt b/docs/gearsandopstates.txt
similarity index 100%
rename from gearsandopstates.txt
rename to docs/gearsandopstates.txt
diff --git a/docs/howtocreatemodule.docx b/docs/howtocreatemodule.docx
new file mode 100644
index 0000000..a83cadd
Binary files /dev/null and b/docs/howtocreatemodule.docx differ
diff --git a/readme.eclipse.txt b/docs/readme.eclipse.txt
similarity index 100%
rename from readme.eclipse.txt
rename to docs/readme.eclipse.txt
diff --git a/eeprom_layout.h b/eeprom_layout.h
index 18ad701..52a676a 100644
--- a/eeprom_layout.h
+++ b/eeprom_layout.h
@@ -2,9 +2,9 @@
* eeprom_layout.h
*
*EEPROM Map. There is support for up to 6 devices: A motor controller, display, charger, BMS, Throttle, and a misc device (EPAS, WOC, etc)
-*
+*
*There is a 256KB eeprom chip which stores these settings. The 4K is allocated to primary storage and 4K is allocated to a "known good"
-* storage location. This leaves most of EEPROM free for something else, probably logging.
+* storage location. This leaves most of EEPROM free for something else, probably logging.
Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
@@ -42,12 +42,50 @@ Devices are considered enabled if their highest ID bit is set (0x8000) otherwise
they're disabled.
This means that valid IDs must be under 0x8000 but that still leaves a couple of open IDs ;)
First device entry is 0xDEAD if valid - otherwise table is initialized
+
+Layout :
+
+Range EE_DEVICES_TABLE to EE_DEVICES_TABLE + (EE_NUM_DEVICES + 1) * 2 - 1
+ 0000-0001 : GEVCU marker (0xDEAD)
+ 0002-0003 : ID of device 1 (enabled if bit 0x8000 of ID is set)
+ 0004-0005 : ID of device 2 (enabled if bit 0x8000 of ID is set)
+ 0006-0007 : ID of device 3 (enabled if bit 0x8000 of ID is set)
+ 0008-0009 : ID of device 4 (enabled if bit 0x8000 of ID is set)
+ ...
+ 0126-0127 : ID of device 63 (enabled if bit 0x8000 of ID is set)
+
+Range EE_DEVICES_TABLE + (EE_NUM_DEVICES + 1) * 2 to EE_DEVICES_BASE - 1
+ 0128-1023 : unused
+
+Range EE_DEVICES_BASE to EE_DEVICES_BASE + EE_NUM_DEVICES * EE_DEVICE_SIZE - 1
+ 1024-1535 : config device 1 (first byte = checksum)
+ 1536-2047 : config device 2 (first byte = checksum)
+ 2048-2559 : config device 3 (first byte = checksum)
+ ...
+ 32768-33279 : config device 63 (first byte = checksum)
+
+Range
+ 33280-34815 : unused
+
+Range EE_LKG_OFFSET to LGK_OFFSET + EE_NUM_DEVICES * EE_DEVICE_SIZE - 1
+ 34816-35327 : lkg config device 1 (first byte = checksum)
+ 35328-35839 : lkg config device 2 (first byte = checksum)
+ ...
+ 66560-67071 : lkg config device 63 (first byte = checksum)
+
+Range EE_SYS_LOG to EE_FAULT_LOG - 1
+ 69632-102399 : system log
+
+Range EE_FAULT_LOG to eeprom size - 1 ?
+ 102400-...
+
*/
-#define EE_DEVICE_TABLE 0 //where is the table of devices found in EEPROM?
+#define EE_DEVICE_TABLE 0 //where is the table of devices found in EEPROM?
+#define EE_NUM_DEVICES 63 // the number of supported device entries
+#define EE_GEVCU_MARKER 0xDEAD // marker at position 0 to identify EEPROM was initialized
#define EE_DEVICE_SIZE 512 //# of bytes allocated to each device
-#define EE_DEVICES_BASE 1024 //start of where devices in the table can use
-#define EE_SYSTEM_START 128
+#define EE_DEVICES_BASE 1024 //start of where devices in the table can use
#define EE_MAIN_OFFSET 0 //offset from start of EEPROM where main config is
#define EE_LKG_OFFSET 34816 //start EEPROM addr where last known good config is
@@ -64,139 +102,136 @@ the end of the stardard data. The below numbers are offsets from the device's ee
*/
//first, things in common to all devices - leave 20 bytes for this
-#define EE_CHECKSUM 0 //1 byte - checksum for this section of EEPROM to makesure it is valid
-#define EE_DEVICE_ID 1 //2 bytes - the value of the ENUM DEVID of this device.
-
-//Motor controller data
-#define EEMC_MAX_RPM 20 //2 bytes, unsigned int for maximum allowable RPM
-#define EEMC_MAX_TORQUE 22 //2 bytes, unsigned int - maximum torque in tenths of a Nm
-#define EEMC_PRECHARGE_RELAY 24 //1 byte - 255 = no precharge relay 0-3 = yes, there is one (and the output is the number stored)
-#define EEMC_CONTACTOR_RELAY 25 //1 byte - 255 = no contactor relay 0-3 = yes there is
-#define EEMC_COOL_FAN 26 //1 byte output controlling external cooling relay
-#define EEMC_COOL_ON 27 //1 bytes temperature at which external cooling is switched on
-#define EEMC_COOL_OFF 28 //1 byte temperature at which external cooling is switched off
-#define EEMC_KILOWATTHRS 29 //4 bytes - capacitance of controller capacitor bank in micro farads (uf) - set to zero to disable RC precharge
-#define EEMC_PRECHARGE_R 33 //2 bytes - Resistance of precharge resistor in tenths of an ohm
-#define EEMC_NOMINAL_V 35 //2 bytes - nominal system voltage to expect (in tenths of a volt)
-#define EEMC_REVERSE_LIMIT 37 //2 bytes - a percentage to knock the requested torque down by while in reverse.
-#define EEMC_RPM_SLEW_RATE 39 //2 bytes - slew rate (rpm/sec) at which speed should change (only in speed mode)
-#define EEMC_TORQUE_SLEW_RATE 41 //2 bytes - slew rate (0.1Nm/sec) at which the torque should change
-#define EEMC_BRAKE_LIGHT 42
-#define EEMC_REV_LIGHT 43
-#define EEMC_ENABLE_IN 44
-#define EEMC_REVERSE_IN 45
-#define EEMC_MOTOR_MODE 46
-
-//throttle data
-#define EETH_MIN_ONE 20 //2 bytes - ADC value of minimum value for first channel
-#define EETH_MAX_ONE 22 //2 bytes - ADC value of maximum value for first channel
-#define EETH_MIN_TWO 24 //2 bytes - ADC value of minimum value for second channel
-#define EETH_MAX_TWO 26 //2 bytes - ADC value of maximum value for second channel
-#define EETH_REGEN_MIN 28 //2 bytes - unsigned int - tenths of a percent (0-1000) of pedal position where regen stops
-#define EETH_FWD 30 //2 bytes - unsigned int - tenths of a percent (0-1000) of pedal position where forward motion starts
-#define EETH_MAP 32 //2 bytes - unsigned int - tenths of a percent (0-1000) of pedal position where forward motion is at 50% throttle
-#define EETH_BRAKE_MIN 34 //2 bytes - ADC value of minimum value for brake input
-#define EETH_BRAKE_MAX 36 //2 bytes - ADC value of max value for brake input
-#define EETH_MAX_ACCEL_REGEN 38 //2 bytes - maximum percentage of throttle to command on accel pedal regen
-#define EETH_MAX_BRAKE_REGEN 40 //2 bytes - maximum percentage of throttle to command for braking regen. Starts at min brake regen and works up to here.
-#define EETH_NUM_THROTTLES 42 //1 byte - How many throttle inputs should we use? (1 or 2)
-#define EETH_THROTTLE_TYPE 43 //1 byte - Allow for different throttle types. For now 1 = Linear pots, 2 = Inverse relationship between pots. See Throttle.h
-#define EETH_MIN_BRAKE_REGEN 44 //2 bytes - the starting level for brake regen as a percentage of throttle
-#define EETH_MIN_ACCEL_REGEN 46 //2 bytes - the starting level for accelerator regen as a percentage of throttle
-#define EETH_REGEN_MAX 48 //2 bytes - unsigned int - tenths of a percent (0-1000) of pedal position where regen is at maximum
-#define EETH_CREEP 50 //2 bytes - percentage of throttle used to simulate creep
-#define EETH_CAR_TYPE 52 //1 byte - type of car for querying the throttle position via CAN bus
-#define EETH_ADC_1 53 //1 byte - which ADC port to use for first throttle input
-#define EETH_ADC_2 54 //1 byte - which ADC port to use for second throttle input
-
-//System Data
-#define EESYS_SYSTEM_TYPE 10 //1 byte - 1 = Old school protoboards 2 = GEVCU2/DUED 3 = GEVCU3 - Defaults to 2 if invalid or not set up
-#define EESYS_RAWADC 20 //1 byte - if not zero then use raw ADC mode (no preconditioning or buffering or differential).
-#define EESYS_ADC0_GAIN 30 //2 bytes - ADC gain centered at 1024 being 1 to 1 gain, thus 512 is 0.5 gain, 2048 is double, etc
-#define EESYS_ADC0_OFFSET 32 //2 bytes - ADC offset from zero - ADC reads 12 bit so the offset will be [0,4095] - Offset is subtracted from read ADC value
-#define EESYS_ADC1_GAIN 34 //2 bytes - ADC gain centered at 1024 being 1 to 1 gain, thus 512 is 0.5 gain, 2048 is double, etc
-#define EESYS_ADC1_OFFSET 36 //2 bytes - ADC offset from zero - ADC reads 12 bit so the offset will be [0,4095] - Offset is subtracted from read ADC value
-#define EESYS_ADC2_GAIN 38 //2 bytes - ADC gain centered at 1024 being 1 to 1 gain, thus 512 is 0.5 gain, 2048 is double, etc
-#define EESYS_ADC2_OFFSET 40 //2 bytes - ADC offset from zero - ADC reads 12 bit so the offset will be [0,4095] - Offset is subtracted from read ADC value
-#define EESYS_ADC3_GAIN 42 //2 bytes - ADC gain centered at 1024 being 1 to 1 gain, thus 512 is 0.5 gain, 2048 is double, etc
-#define EESYS_ADC3_OFFSET 44 //2 bytes - ADC offset from zero - ADC reads 12 bit so the offset will be [0,4095] - Offset is subtracted from read ADC value
-
-#define EESYS_CAN0_BAUD 100 //2 bytes - Baud rate of CAN0 in 1000's of baud. So a value of 500 = 500k baud. Set to 0 to disable CAN0
-#define EESYS_CAN1_BAUD 102 //2 bytes - Baud rate of CAN1 in 1000's of baud. So a value of 500 = 500k baud. Set to 0 to disable CAN1
-#define EESYS_SERUSB_BAUD 104 //2 bytes - Baud rate of serial debugging port. Multiplied by 10 to get baud. So 115200 baud will be set as 11520
-#define EESYS_TWI_BAUD 106 //2 bytes - Baud for TWI in 1000's just like CAN bauds. So 100k baud is set as 100
-#define EESYS_TICK_RATE 108 //2 bytes - # of system ticks per second. Can range the full 16 bit value [1, 65536] which yields ms rate of [15us, 1000ms]
-
-//We store the current system time from the RTC in EEPROM every so often.
-//RTC is not battery backed up on the Due so a power failure will reset it.
-//These storage spaces let the firmware reload the last knowm time to bootstrap itself
-//as much as possible. The hope is that we'll be able to get access to internet eventually
-//and use NTP to get the real time.
-#define EESYS_RTC_TIME 150 //4 bytes - BCD packed version of the current time in the same format as it is stored in RTC chip
-#define EESYS_RTC_DATE 154 //4 bytes - BCD version of date in format of RTC chip
-
-//Technically there are two different canbus systems in use. The MCP2515 has 2 masks and 5 filters. The Arduino DUE
-//Has 8 masks and 8 filters potentially (not really, you do need transmit boxes too). So, the most masks and filters
-//we could ever set is 7 (using one mb as transmit) so support accordingly.
-
-#define EESYS_CAN_RX_COUNT 199 //1 byte - how many mailboxes to use for RX on the Due. On the Macchina it is always 5.
-#define EESYS_CAN_MASK0 200 //4 bytes - first canbus mask - bit 31 sets whether it is extended or not (set = extended)
-#define EESYS_CAN_FILTER0 204 //4 bytes - first canbus filter - uses mask 0 on Due and Macchina
-#define EESYS_CAN_MASK1 208 //4 bytes - second canbus mask - bit 31 sets whether it is extended or not (set = extended)
-#define EESYS_CAN_FILTER1 212 //4 bytes - second canbus filter - uses mask 0 on Macchina, Mask 1 on Due
-#define EESYS_CAN_MASK2 216 //4 bytes - third canbus mask - bit 31 sets whether it is extended or not (set = extended)
-#define EESYS_CAN_FILTER2 220 //4 bytes - third canbus filter - uses mask 1 on Macchina, Mask 2 on Due
-#define EESYS_CAN_MASK3 224 //4 bytes - fourth canbus mask - bit 31 sets whether it is extended or not (set = extended)
-#define EESYS_CAN_FILTER3 228 //4 bytes - fourth canbus filter - uses mask 1 on Macchina, Mask 3 on Due
-#define EESYS_CAN_MASK4 232 //4 bytes - fifth canbus mask - bit 31 sets whether it is extended or not (set = extended)
-#define EESYS_CAN_FILTER4 236 //4 bytes - fifth canbus filter - uses mask 1 on Macchina, Mask 4 on Due
-#define EESYS_CAN_MASK5 240 //4 bytes - sixth canbus mask - bit 31 sets whether it is extended or not (set = extended)
-#define EESYS_CAN_FILTER5 244 //4 bytes - sixth canbus filter - not valid on Macchina, Mask 5 on Due
-#define EESYS_CAN_MASK6 248 //4 bytes - seventh canbus mask - bit 31 sets whether it is extended or not (set = extended)
-#define EESYS_CAN_FILTER6 252 //4 bytes - seventh canbus filter - not valid on Macchina, Mask 6 on Due
-
-//Allow for a few defined WIFI SSIDs that the GEVCU will try to automatically connect to.
-#define EESYS_WIFI0_SSID 300 //32 bytes - the SSID to create or use (prefixed with ! if create ad-hoc)
-#define EESYS_WIFI0_CHAN 332 //1 byte - the wifi channel (1 - 11) to use
-#define EESYS_WIFI0_DHCP 333 //1 byte - DHCP mode, 0 = off, 1 = server, 2 = client
-#define EESYS_WIFI0_MODE 334 //1 byte - 0 = B, 1 = G
-#define EESYS_WIFI0_IPADDR 335 //4 bytes - IP address to use if DHCP is off
-#define EESYS_WIFI0_KEY 339 //40 bytes - the security key (13 bytes for WEP, 8 - 83 for WPA but only up to 40 here
-
-#define EESYS_WIFI1_SSID 400 //32 bytes - the SSID to create or use (prefixed with ! if create ad-hoc)
-#define EESYS_WIFI1_CHAN 432 //1 byte - the wifi channel (1 - 11) to use
-#define EESYS_WIFI1_DHCP 433 //1 byte - DHCP mode, 0 = off, 1 = server, 2 = client
-#define EESYS_WIFI1_MODE 434 //1 byte - 0 = B, 1 = G
-#define EESYS_WIFI1_IPADDR 435 //4 bytes - IP address to use if DHCP is off
-#define EESYS_WIFI1_KEY 439 //40 bytes - the security key (13 bytes for WEP, 8 - 83 for WPA but only up to 40 here
-
-#define EESYS_WIFI2_SSID 500 //32 bytes - the SSID to create or use (prefixed with ! if create ad-hoc)
-#define EESYS_WIFI2_CHAN 532 //1 byte - the wifi channel (1 - 11) to use
-#define EESYS_WIFI2_DHCP 533 //1 byte - DHCP mode, 0 = off, 1 = server, 2 = client
-#define EESYS_WIFI2_MODE 534 //1 byte - 0 = B, 1 = G
-#define EESYS_WIFI2_IPADDR 535 //4 bytes - IP address to use if DHCP is off
-#define EESYS_WIFI2_KEY 539 //40 bytes - the security key (13 bytes for WEP, 8 - 83 for WPA but only up to 40 here
-
-//If the above networks can't be joined then try to form our own adhoc network
-//with the below parameters.
-#define EESYS_WIFIX_SSID 579 //32 bytes - the SSID to create or use (prefixed with ! if create ad-hoc)
-#define EESYS_WIFIX_CHAN 611 //1 byte - the wifi channel (1 - 11) to use
-#define EESYS_WIFIX_DHCP 612 //1 byte - DHCP mode, 0 = off, 1 = server, 2 = client
-#define EESYS_WIFIX_MODE 613 //1 byte - 0 = B, 1 = G
-#define EESYS_WIFIX_IPADDR 614 //4 bytes - IP address to use if DHCP is off
-#define EESYS_WIFIX_KEY 618 //40 bytes - the security key (13 bytes for WEP, 8 - 83 for WPA but only up to 40 here
-
-#define EESYS_LOG_LEVEL 658 //1 byte - the log level
-#define EESYS_AMPHOURS 659 //1 byte - ???
-#define EESYS_BRAKELIGHT 660 //1 byte -
-#define EESYS_xxxx 661 //1 byte -
-
-#define EEFAULT_VALID 0 //1 byte - Set to value of 0xB2 if fault data has been initialized
-#define EEFAULT_READPTR 1 //2 bytes - index where reading should start (first unacknowledged fault)
-#define EEFAULT_WRITEPTR 3 //2 bytes - index where writing should occur for new faults
-#define EEFAULT_RUNTIME 5 //4 bytes - stores the number of seconds (in tenths) that the system has been turned on for - total time ever
-#define EEFAULT_FAULTS_START 10 //a bunch of faults stored one after the other start at this location
-
+#define EE_CHECKSUM 0 //1 byte - checksum for this section of EEPROM to makesure it is valid
+
+// Motor controller data
+#define EEMC_MAX_RPM 20 //2 bytes, unsigned int for maximum allowable RPM
+#define EEMC_MAX_TORQUE 22 //2 bytes, unsigned int - maximum torque in tenths of a Nm
+#define EEMC_NOMINAL_V 46 //2 bytes - nominal system voltage to expect (in tenths of a volt)
+#define EEMC_REVERSE_LIMIT 48 //2 bytes - a percentage to knock the requested torque down by while in reverse.
+#define EEMC_SLEW_RATE_REGEN 50 // 2 bytes - slew rate regen/brake
+#define EEMC_SLEW_RATE_MOTOR 52 // 2 bytes - slew rate motoring
+#define EEMC_MAX_MECH_POWER_MOTOR 54 // 2 bytes - max mechanical power motoring in 4W steps
+#define EEMC_MAX_MECH_POWER_REGEN 56 // 2 bytes - max mechanical power regen in 4W steps
+#define EEMC_DC_VOLT_LIMIT_MOTOR 58 // 2 bytes - DC volt limit for motoring in 0.1V
+#define EEMC_DC_VOLT_LIMIT_REGEN 60 // 2 bytes - DC volt limit for regen in 0.1V
+#define EEMC_DC_CURRENT_LIMIT_MOTOR 62 // 2 bytes - DC current limit for motoring in 0.1A
+#define EEMC_DC_CURRENT_LIMIT_REGEN 64 // 2 bytes - DC current limit for regen in 0.1A
+#define EEMC_OSCILLATION_LIMITER 66 // 1 byte - flag to enable oscillation limiter (1=true/0=false)
+#define EEMC_INVERT_DIRECTION 67 // 1 byte - flag to indicate if the motor's direction should be inverted
+#define EEMC_POWER_MODE 68 // 1 byte - speed or torque mode
+#define EEMC_CREEP_LEVEL 69 // 1 byte - percentage of throttle used to simulate creep
+#define EEMC_CREEP_SPEED 70 // 2 bytes - max speed for creep
+#define EEMC_BRAKE_HOLD 72 // 1 byte - percentage of max torque to achieve brake hold (0=off)
+#define EEMC_UNUSED3 73 // 1 byte - unused
+#define EEMC_BRAKE_HOLD_COEFF 74 // 1 byte - brake hold force coefficient
+#define EEMC_CRUISE_KP 75 // 2 byte - Kp value for cruise control PID
+#define EEMC_CRUISE_KI 77 // 2 byte - Ki value for cruise control PID
+#define EEMC_CRUISE_KD 79 // 2 byte - Kd value for cruise control PID
+#define EEMC_CRUISE_LONG_PRESS_DELTA 81 // 2 byte - delta to target speed when pressing +/- button long (kph/rpm)
+#define EEMC_CRUISE_STEP_DELTA 83 // 2 byte - delta to actual speen wehn pressing +/- button a short time
+#define EEMC_CRUISE_USE_RPM 85 // 1 byte - flag if true, cruise control uses rpm, if false kph to control vehicle speed
+
+// Throttle data
+#define EETH_LEVEL_MIN 20 //2 bytes - ADC value of minimum value for first channel
+#define EETH_LEVEL_MAX 22 //2 bytes - ADC value of maximum value for first channel
+#define EETH_LEVEL_MIN_TWO 24 //2 bytes - ADC value of minimum value for second channel
+#define EETH_LEVEL_MAX_TWO 26 //2 bytes - ADC value of maximum value for second channel
+#define EETH_REGEN_MIN 28 //2 bytes - unsigned int - tenths of a percent (0-1000) of pedal position where regen stops
+#define EETH_FWD 30 //2 bytes - unsigned int - tenths of a percent (0-1000) of pedal position where forward motion starts
+#define EETH_MAP 32 //2 bytes - unsigned int - tenths of a percent (0-1000) of pedal position where forward motion is at 50% throttle
+#define EETH_BRAKE_MIN 34 //2 bytes - ADC value of minimum value for brake input
+#define EETH_BRAKE_MAX 36 //2 bytes - ADC value of max value for brake input
+#define EETH_MAX_ACCEL_REGEN 38 //2 bytes - maximum percentage of throttle to command on accel pedal regen
+#define EETH_MAX_BRAKE_REGEN 40 //2 bytes - maximum percentage of throttle to command for braking regen. Starts at min brake regen and works up to here.
+#define EETH_NUM_THROTTLES 42 //1 byte - How many throttle inputs should we use? (1 or 2)
+#define EETH_THROTTLE_TYPE 43 //1 byte - Allow for different throttle types. For now 1 = Linear pots, 2 = Inverse relationship between pots. See Throttle.h
+#define EETH_MIN_BRAKE_REGEN 44 //2 bytes - the starting level for brake regen as a percentage of throttle
+#define EETH_MIN_ACCEL_REGEN 46 //2 bytes - the starting level for accelerator regen as a percentage of throttle
+#define EETH_REGEN_MAX 48 //2 bytes - unsigned int - tenths of a percent (0-1000) of pedal position where regen is at maximum
+#define EETH_UNUSED1 50 //2 bytes -
+#define EETH_UNUSED2 52 //1 byte - unused
+#define EETH_ADC_1 53 //1 byte - which ADC port to use for first throttle input
+#define EETH_ADC_2 54 //1 byte - which ADC port to use for second throttle input
+
+// DC-DC converter data
+#define EEDC_BOOST_MODE 20 // 1 byte, boost mode = 1, buck mode = 0
+#define EEDC_DEBUG_MODE 21 // 1 byte, debug mode enabled
+#define EEDC_LOW_VOLTAGE 22 // 2 byte, low voltage
+#define EEDC_HIGH_VOLTAGE 24 // 2 byte, hich voltage
+#define EEDC_HV_UNDERVOLTAGE_LIMIT 26 // 2 byte, HV undervoltage limit
+#define EEDC_LV_BUCK_CURRENT_LIMIT 28 // 2 byte, LV buck current limit
+#define EEDC_HV_BUCK_CURRENT_LIMIT 30 // 2 byte, HV buck current limit
+#define EEDC_LV_UNDERVOLTAGE_LIMIT 32 // 2 byte, LV undervoltage limit
+#define EEDC_LV_BOOST_CURRENT_LIMIT 34 // 2 byte, LV boost current limit
+#define EEDC_HV_BOOST_CURRENT_LIMIT 36 // 2 byte, HV boost current limit
+
+// Charger data
+#define EECH_MAX_INPUT_CURRENT 20 // 2 bytes, max mains current in 0.1A
+#define EECH_CONSTANT_CURRENT 22 // 2 bytes, constant current in 0.1A
+#define EECH_CONSTANT_VOLTAGE 24 // 2 bytes, constant voltage in 0.1V
+#define EECH_TERMINATE_CURRENT 26 // 2 bytes, terminate current in 0.1A
+#define EECH_MIN_BATTERY_VOLTAGE 28 // 2 bytes, minimum battery voltage to start charging in 0.1V
+#define EECH_MAX_BATTERY_VOLTAGE 30 // 2 bytes, maximum battery voltage to charge in 0.1V
+#define EECH_MIN_BATTERY_TEMPERATURE 32 // 2 bytes, minimum battery temp to charge in 0.1deg C
+#define EECH_MAX_BATTERY_TEMPERATURE 34 // 2 bytes, maximum battery temp to charge in 0.1deg C
+#define EECH_MAX_AMPERE_HOURS 36 // 2 bytes, maximum Ah to charge in 0.1Ah
+#define EECH_MAX_CHARGE_TIME 38 // 2 bytes, maximum charge time in minutes
+#define EECH_DERATING_TEMPERATURE 40 // 2 bytes, 0.1Ah per deg Celsius
+#define EECH_DERATING_REFERENCE 42 // 2 bytes, 0.1 deg Celsius where derating will reach 0 Amp
+#define EECH_HYSTERESE_STOP 44 // 2 bytes, temperature where charging is interrupted in 0.1deg C
+#define EECH_HYSTERESE_RESUME 46 // 2 bytes, temperature where chargin is resumed in 0.1deg C
+#define EECH_MEASURE_TIME 48 // 2 bytes, time to measure input voltage at idle in ms
+#define EECH_MEASURE_CURRENT 50 // 2 bytes, current to apply during voltage measurement in 0.1V
+#define EECH_VOLTAGE_DROP 52 // 1 byte, divisor of input voltage by which it may drop
+#define EECH_INITIAL_INPUT_CURRENT 53 // 2 byte, initial value of max input current in 0.1A
+
+// System I/O
+#define EESIO_SYSTEM_TYPE 10 //1 byte - 1 = Old school protoboards 2 = GEVCU2/DUED 3 = GEVCU3 - Defaults to 2 if invalid or not set up
+#define EESIO_LOG_LEVEL 11 //1 byte - the log level
+#define EESIO_ENEGRY_CONSUMPTION 12 //4 bytes - accumulated power consumption
+#define EESIO_ENABLE_INPUT 45 // 1 byte - digital input to enable GEVCU (255 = no input required)
+#define EESIO_PRECHARGE_MILLIS 46 // 2 bytes - milliseconds for precharge cycle
+#define EESIO_SECONDARY_CONTACTOR_OUTPUT 48 // 1 byte - digital output for secondary contactor (255 = no output)
+#define EESIO_PRECHARGE_RELAY_OUTPUT 49 // 1 byte - digital output for pre-charge relay (255 = no output)
+#define EESIO_MAIN_CONTACTOR_OUTPUT 50 // 1 byte - digital output for main contactor (255 = no output)
+#define EESIO_ENABLE_MOTOR_OUTPUT 51 // 1 byte - digital output to enable motor controller (255 = no output)
+#define EESIO_COOLING_FAN_OUTPUT 52 // 1 byte - digital output to control external cooling relay (255 = no output)
+#define EESIO_COOLING_TEMP_ON 53 // 1 byte - temperature at which external cooling is switched on
+#define EESIO_COOLING_TEMP_OFF 54 // 1 byte - temperature at which external cooling is switched off
+#define EESIO_BRAKE_LIGHT_OUTPUT 55 // 1 byte - digital output for brake light at regen (255 = no output)
+#define EESIO_REVERSE_LIGHT_OUTPUT 56 // 1 byte - digital output for reverse light (255 = no output)
+#define EESIO_INTERLOCK_INPUT 57 // 1 byte - digital input for interlock signal (255 = no input)
+#define EESIO_CHARGE_POWER_AVAILABLE_INPUT 58 // 1 byte - digital input for charge power available signal (255 = no input)
+#define EESIO_FAST_CHARGE_CONTACTOR_OUTPUT 59 // 1 byte - digital output for fast charge contactor (255 = no output)
+#define EESIO_ENABLE_CHARGER_OUTPUT 60 // 1 byte - digital output for charger enable signal (255 = no output)
+#define EESIO_ENABLE_DCDC_OUTPUT 61 // 1 byte - digital output for DCDC converter enable signal (255 = no output)
+#define EESIO_ENABLE_HEATER_OUTPUT 62 // 1 byte - digital output for heater enable signal (255 = no output)
+#define EESIO_HEATER_VALVE_OUTPUT 63 // 1 byte - digital output for heater valve signal (255 = no output)
+#define EESIO_HEATER_PUMP_OUTPUT 64 // 1 byte - digital output for heater pump relay (255 = no output)
+#define EESIO_COOLING_PUMP_OUTPUT 65 // 1 byte - digital output for cooling pump relay (255 = no output)
+#define EESIO_WARNING_OUTPUT 66 // 1 byte - digital output for warning signal (255 = no output)
+#define EESIO_POWER_LIMITATION_OUTPUT 67 // 1 byte - digital output for power limitation signal (255 = no output)
+#define EESIO_REVERSE_INPUT 68 // 1 byte - digital input for reverse signal (255 = no input)
+#define EESIO_POWER_STEERING_OUTPUT 69 // 1 byte - digital output for power steering
+#define EESIO_CAR_TYPE 70 // 1 byte - car type
+#define EESIO_STATE_OF_CHARGE_OUTPUT 71 // 1 byte - digital output for indication of SoC (255 = no output)
+#define EESIO_GEAR_CHANGE_INPUT 72 // 1 byte - digital input for gear change signal (255 = no input)
+#define EESIO_STATUS_LIGHT_OUTPUT 73 // 1 byte - digital oupt for PWM operated status light
+#define EESIO_HEATER_TEMPERATURE_ON 74 // 1 byte - temp in deg C where heater is enabled
+#define EESIO_ABS_INPUT 75 // 1 byte - digital input for ABS signal (255 = no output)
+
+// CanOBD2
+#define EEOBD2_CAN_BUS_RESPOND 10 // 1 byte - which can bus should we respond to OBD2 requests (0=ev, 1=car, 255=ignore)
+#define EEOBD2_CAN_ID_OFFSET_RESPOND 11 // 1 byte - offset for can id on wich we listen to incoming requests (0-7)
+#define EEOBD2_CAN_BUS_POLL 12 // 1 byte - which can bus should we poll OBD2 data from (0=ev, 1=car, 255=ignore)
+#define EEOBD2_CAN_ID_OFFSET_POLL 13 // 1 byte - offset for can id on which we will request OBD2 data from (0-7, 255=broadcast)
+
+// Fault Handler
+#define EEFAULT_VALID 0 //1 byte - Set to value of 0xB2 if fault data has been initialized
+#define EEFAULT_READPTR 1 //2 bytes - index where reading should start (first unacknowledged fault)
+#define EEFAULT_WRITEPTR 3 //2 bytes - index where writing should occur for new faults
+#define EEFAULT_RUNTIME 5 //4 bytes - stores the number of seconds (in tenths) that the system has been turned on for - total time ever
+#define EEFAULT_FAULTS_START 10 //a bunch of faults stored one after the other start at this location
#endif
-
diff --git a/ichip_2128.cpp b/ichip_2128.cpp
deleted file mode 100644
index c250f59..0000000
--- a/ichip_2128.cpp
+++ /dev/null
@@ -1,942 +0,0 @@
-/*
- * ichip_2128.cpp
- *
- * Class to interface with the ichip 2128 based wifi adapter we're using on our board
- *
- Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
-
- 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 "ichip_2128.h"
-
-/*
- * Constructor. Assign serial interface to use for ichip communication
- */
-ICHIPWIFI::ICHIPWIFI() {
- prefsHandler = new PrefHandler(ICHIP2128);
-
- uint8_t sys_type;
- sysPrefs->read(EESYS_SYSTEM_TYPE, &sys_type);
- if (sys_type == 3 || sys_type == 4)
- serialInterface = &Serial2;
- else //older hardware used this instead
- serialInterface = &Serial3;
-
- commonName = "WIFI (iChip2128)";
-}
-
-/*
- * Constructor. Pass serial interface to use for ichip communication
- */
-ICHIPWIFI::ICHIPWIFI(USARTClass *which) {
- prefsHandler = new PrefHandler(ICHIP2128);
- serialInterface = which;
-}
-
-/*
- * Initialization of hardware and parameters
- */
-void ICHIPWIFI::setup() {
-
- Logger::info("add device: iChip 2128 WiFi (id: %X, %X)", ICHIP2128, this);
-
- TickHandler::getInstance()->detach(this);
-
- //MSEL pin
- pinMode(18, OUTPUT);
- digitalWrite(18, HIGH);
-
- //RESET pin
- pinMode(42, OUTPUT);
- digitalWrite(42, HIGH);
-
- tickCounter = 0;
- ibWritePtr = 0;
- psWritePtr = 0;
- psReadPtr = 0;
- listeningSocket = 0;
-
- lastSentTime = millis();
- lastSentState = IDLE;
- lastSentCmd = String("");
-
- activeSockets[0] = -1;
- activeSockets[1] = -1;
- activeSockets[2] = -1;
- activeSockets[3] = -1;
-
- state = IDLE;
-
- didParamLoad = false;
- didTCPListener = false;
-
- serialInterface->begin(115200);
-
- paramCache.brakeNotAvailable = true;
-
- elmProc = new ELM327Processor();
-
- TickHandler::getInstance()->attach(this, CFG_TICK_INTERVAL_WIFI);
-
-}
-
-//A version of sendCmd that defaults to SET_PARAM which is what most of the code used to assume.
-void ICHIPWIFI::sendCmd(String cmd) {
- sendCmd(cmd, SET_PARAM);
-}
-
-/*
- * Send a command to ichip. The "AT+i" part will be added.
- * If the comm channel is busy it buffers the command
- */
-void ICHIPWIFI::sendCmd(String cmd, ICHIP_COMM_STATE cmdstate) {
- if (state != IDLE) { //if the comm is tied up then buffer this parameter for sending later
- sendingBuffer[psWritePtr].cmd = cmd;
- sendingBuffer[psWritePtr].state = cmdstate;
- psWritePtr = (psWritePtr + 1) & 63;
- if (Logger::isDebug()) {
- String temp = "Buffer cmd: " + cmd;
- Logger::debug(ICHIP2128, (char *)temp.c_str());
- }
- }
- else { //otherwise, go ahead and blast away
- serialInterface->write(Constants::ichipCommandPrefix);
- serialInterface->print(cmd);
- serialInterface->write(13);
- state = cmdstate;
- lastSentTime = millis();
- lastSentCmd = String(cmd);
- lastSentState = cmdstate;
-
- if (Logger::isDebug()) {
- String temp = "Send to ichip cmd: " + cmd;
- Logger::debug(ICHIP2128, (char *)temp.c_str());
- }
- }
-}
-
-void ICHIPWIFI::sendToSocket(int socket, String data) {
- char buff[6];
- sprintf(buff, "%03i", socket);
- String temp = "SSND%%:" + String(buff);
- sprintf(buff, ",%i:", data.length());
- temp = temp + String(buff) + data;
- sendCmd(temp, SEND_SOCKET);
-}
-
-/*
- * Periodic updates of parameters to ichip RAM.
- * Also query for changed parameters of the config page.
- */
-//TODO: See the processing function below for a more detailed explanation - can't send so many setParam commands in a row
-void ICHIPWIFI::handleTick() {
- MotorController* motorController = DeviceManager::getInstance()->getMotorController();
- Throttle *accelerator = DeviceManager::getInstance()->getAccelerator();
- Throttle *brake = DeviceManager::getInstance()->getBrake();
- static int pollListening = 0;
- static int pollSocket = 0;
- uint32_t ms = millis();
- char buff[6];
- uint8_t brklt;
- tickCounter++;
-
- if (ms < 1000) return; //wait 10 seconds for things to settle before doing a thing
-
- // Do a delayed parameter load once about a second after startup
- if (!didParamLoad && ms > 5000) {
- loadParameters();
- Logger::console("Wifi Parameters loaded...");
- paramCache.bitfield1 = motorController->getStatusBitfield1();
- setParam(Constants::bitfield1, paramCache.bitfield1);
- paramCache.bitfield2 = motorController->getStatusBitfield2();
- setParam(Constants::bitfield2, paramCache.bitfield2);
- // DeviceManager::getInstance()->updateWifiByID(BRUSA_DMC5);
-
- didParamLoad = true;
- }
-
- //At 2 seconds start up a listening socket for OBDII
- if (!didTCPListener && ms > 12000) {
- sendCmd("LTCP:2000,4", START_TCP_LISTENER);
- didTCPListener = true;
- }
-
- if (listeningSocket > 9) {
- pollListening++;
- if (pollListening > 8) {
- pollListening = 0;
- char buff[5];
- sprintf(buff, "%u", listeningSocket);
- String temp = "LSST:" + String(buff);
- sendCmd(temp, GET_ACTIVE_SOCKETS);
- }
- }
-
- //read any information waiting on active sockets
- for (int c = 0; c < 4; c++)
- if (activeSockets[c] != -1) {
- sprintf(buff, "%03i", activeSockets[c]);
- String temp = "SRCV:" + String(buff) + ",80";
- sendCmd(temp, GET_SOCKET);
- }
-
- //TODO:Testing line below. Remove it.
- //return;
-
-
- // make small slices so the main loop is not blocked for too long
- if (tickCounter == 1) {
- if (motorController) {
- //Logger::console("Wifi tick counter 1...");
-
- paramCache.timeRunning = ms;
- setParam(Constants::timeRunning, getTimeRunning());
-
- if ( paramCache.torqueRequested != motorController->getTorqueRequested() ) {
- paramCache.torqueRequested = motorController->getTorqueRequested();
- setParam(Constants::torqueRequested, paramCache.torqueRequested / 10.0f, 1);
- }
- if ( paramCache.torqueActual != motorController->getTorqueActual() ) {
- paramCache.torqueActual = motorController->getTorqueActual();
- setParam(Constants::torqueActual, paramCache.torqueActual / 10.0f, 1);
- }
- }
- if (accelerator) {
- RawSignalData *rawSignal = accelerator->acquireRawSignal();
- if ( paramCache.throttle != rawSignal->input1) {
- paramCache.throttle = rawSignal->input1;
- setParam(Constants::throttle, paramCache.throttle);
-
- /*if ( paramCache.throttle != accelerator->getLevel() ) {
- paramCache.throttle = accelerator->getLevel();
- if (paramCache.throttle<-600){paramCache.throttle=-600;}
- setParam(Constants::throttle, paramCache.throttle / 10.0f, 1);*/
- }
- }
- if (brake) {
- RawSignalData *rawSignal = brake->acquireRawSignal();
- if ( paramCache.brake != rawSignal->input1) {
- paramCache.brake = rawSignal->input1;
- paramCache.brakeNotAvailable = false;
- setParam(Constants::brake, paramCache.brake);
-
- /*if ( paramCache.brake != brake->getLevel() ) {
- paramCache.brake = brake->getLevel();
- paramCache.brakeNotAvailable = false;
- setParam(Constants::brake, paramCache.brake / 10.0f, 1);*/
- }
- } else {
- if ( paramCache.brakeNotAvailable == true ) {
- paramCache.brakeNotAvailable = false; // no need to keep sending this
- setParam(Constants::brake, Constants::notAvailable);
- }
- }
- } else if (tickCounter == 2) {
- if (motorController) {
- //Logger::console("Wifi tick counter 2...");
- if ( paramCache.speedRequested != motorController->getSpeedRequested() ) {
- paramCache.speedRequested = motorController->getSpeedRequested();
- setParam(Constants::speedRequested, paramCache.speedRequested);
- }
- if ( paramCache.speedActual != motorController->getSpeedActual() ) {
- paramCache.speedActual = motorController->getSpeedActual();
- if (paramCache.speedActual<0) paramCache.speedActual=0;
- if (paramCache.speedActual>10000) paramCache.speedActual=10000;
- setParam(Constants::speedActual, paramCache.speedActual);
- }
- if ( paramCache.dcVoltage != motorController->getDcVoltage() ) {
- paramCache.dcVoltage = motorController->getDcVoltage();
- if(paramCache.dcVoltage<1000) paramCache.dcVoltage=1000; //Limits of the gage display
- if(paramCache.dcVoltage>4500) paramCache.dcVoltage=4500;
-
- setParam(Constants::dcVoltage, paramCache.dcVoltage / 10.0f, 1);
- }
- if ( paramCache.dcCurrent != motorController->getDcCurrent() ) {
- paramCache.dcCurrent = motorController->getDcCurrent();
- setParam(Constants::dcCurrent, paramCache.dcCurrent / 10.0f, 1);
- }
- if ( paramCache.prechargeR != motorController->getprechargeR() ) {
- paramCache.prechargeR = motorController->getprechargeR();
- setParam(Constants::prechargeR, (uint16_t)paramCache.prechargeR);
- }
-
- if ( paramCache.prechargeRelay != motorController->getprechargeRelay() ) {
- paramCache.prechargeRelay = motorController->getprechargeRelay();
- setParam(Constants::prechargeRelay, (uint8_t) paramCache.prechargeRelay);
- //Logger::console("Precharge Relay %i", paramCache.prechargeRelay);
- //Logger::console("motorController:prechargeRelay:%d, paramCache.prechargeRelay:%d, Constants:prechargeRelay:%s", motorController->getprechargeRelay(),paramCache.prechargeRelay, Constants::prechargeRelay);
- }
-
- if ( paramCache.mainContactorRelay != motorController->getmainContactorRelay() ) {
- paramCache.mainContactorRelay = motorController->getmainContactorRelay();
- setParam(Constants::mainContactorRelay, (uint8_t) paramCache.mainContactorRelay);
- }
- }
- } else if (tickCounter == 3) {
- if (motorController) {
- //Logger::console("Wifi tick counter 2...");
- if ( paramCache.acCurrent != motorController->getAcCurrent() ) {
- paramCache.acCurrent = motorController->getAcCurrent();
- setParam(Constants::acCurrent, paramCache.acCurrent / 10.0f, 1);
- }
-
- //if ( paramCache.kiloWattHours != motorController->getkiloWattHours()/3600000 ) {
- paramCache.kiloWattHours = motorController->getKiloWattHours()/3600000;
- if(paramCache.kiloWattHours<0)paramCache.kiloWattHours = 0;
- if(paramCache.kiloWattHours>300)paramCache.kiloWattHours = 300;
- setParam(Constants::kiloWattHours, paramCache.kiloWattHours / 10.0f, 1);
- //}
-
- if ( paramCache.nominalVolt != motorController->getnominalVolt()/10 ){
- paramCache.nominalVolt = motorController->getnominalVolt()/10;
- setParam(Constants::nominalVolt, paramCache.nominalVolt);
- }
-
- if ( paramCache.bitfield1 != motorController->getStatusBitfield1() ) {
- paramCache.bitfield1 = motorController->getStatusBitfield1();
- setParam(Constants::bitfield1, paramCache.bitfield1);
- }
- if ( paramCache.bitfield2 != motorController->getStatusBitfield2() ) {
- paramCache.bitfield2 = motorController->getStatusBitfield2();
- setParam(Constants::bitfield2, paramCache.bitfield2);
- }
- if ( paramCache.bitfield3 != motorController->getStatusBitfield3() ) {
- paramCache.bitfield3 = motorController->getStatusBitfield3();
- setParam(Constants::bitfield3, paramCache.bitfield3);
- }
- if ( paramCache.bitfield4 != motorController->getStatusBitfield4() ) {
- paramCache.bitfield4 = motorController->getStatusBitfield4();
- setParam(Constants::bitfield4, paramCache.bitfield4);
- }
-
- }
- } else if (tickCounter == 4) {
- if (motorController) {
- // Logger::console("Wifi tick counter 4...");
- if ( paramCache.running != motorController->isRunning() ) {
- paramCache.running = motorController->isRunning();
- setParam(Constants::running, (paramCache.running ? Constants::trueStr : Constants::falseStr));
- }
- if ( paramCache.faulted != motorController->isFaulted() ) {
- paramCache.faulted = motorController->isFaulted();
- setParam(Constants::faulted, (paramCache.faulted ? Constants::trueStr : Constants::falseStr));
- }
- if ( paramCache.warning != motorController->isWarning() ) {
- paramCache.warning = motorController->isWarning();
- setParam(Constants::warning, (paramCache.warning ? Constants::trueStr : Constants::falseStr));
- }
- if ( paramCache.gear != motorController->getSelectedGear() ) {
- paramCache.gear = motorController->getSelectedGear();
- setParam(Constants::gear, (uint16_t)paramCache.gear);
- }
-
- if ( paramCache.coolFan != motorController->getCoolFan() ) {
- paramCache.coolFan = motorController->getCoolFan();
- setParam(Constants::coolFan, (uint8_t) paramCache.coolFan);
- }
-
- if ( paramCache.coolOn != motorController->getCoolOn() ) {
- paramCache.coolOn = motorController->getCoolOn();
- setParam(Constants::coolOn, (uint8_t) paramCache.coolOn);
- }
-
- if ( paramCache.coolOff != motorController->getCoolOff() ) {
- paramCache.coolOff = motorController->getCoolOff();
- setParam(Constants::coolOff, (uint8_t) paramCache.coolOff);
- }
-
- if ( paramCache.brakeLight != motorController->getBrakeLight() ) {
- paramCache.brakeLight = motorController->getBrakeLight();
- setParam(Constants::brakeLight, (uint8_t) paramCache.brakeLight);
- }
-
- if ( paramCache.revLight != motorController->getRevLight() ) {
- paramCache.revLight = motorController->getRevLight();
- setParam(Constants::revLight, (uint8_t) paramCache.revLight);
- }
-
- if ( paramCache.enableIn != motorController->getEnableIn() ) {
- paramCache.enableIn = motorController->getEnableIn();
- setParam(Constants::enableIn, (uint8_t) paramCache.enableIn);
- }
- if ( paramCache.reverseIn != motorController->getReverseIn() ) {
- paramCache.reverseIn = motorController->getReverseIn();
- setParam(Constants::reverseIn, (uint8_t) paramCache.reverseIn);
- }
-
- }
- } else if (tickCounter > 4) {
- if (motorController) {
- // Logger::console("Wifi tick counter 5...");
- if ( paramCache.tempMotor != motorController->getTemperatureMotor() ) {
- paramCache.tempMotor = motorController->getTemperatureMotor();
- setParam(Constants::tempMotor, paramCache.tempMotor / 10.0f, 1);
- }
- if ( paramCache.tempInverter != motorController->getTemperatureInverter() ) {
- paramCache.tempInverter = motorController->getTemperatureInverter();
- setParam(Constants::tempInverter, paramCache.tempInverter / 10.0f, 1);
- }
- if ( paramCache.tempSystem != motorController->getTemperatureSystem() ) {
- paramCache.tempSystem = motorController->getTemperatureSystem();
- setParam(Constants::tempSystem, paramCache.tempSystem / 10.0f, 1);
- }
-
- if (paramCache.powerMode != motorController->getPowerMode() ) {
- paramCache.powerMode = motorController->getPowerMode();
- setParam(Constants::motorMode, (uint8_t)paramCache.powerMode);
- }
-
- //if ( paramCache.mechPower != motorController->getMechanicalPower() ) {
- paramCache.mechPower = motorController->getMechanicalPower();
- if (paramCache.mechPower<-250)paramCache.mechPower=-250;
- if (paramCache.mechPower>1500)paramCache.mechPower=1500;
- setParam(Constants::mechPower, paramCache.mechPower / 10.0f, 1);
- //}
- }
- tickCounter = 0;
- getNextParam();
- }
-}
-
-/*
- * Calculate the runtime in hh:mm:ss
- This runtime calculation is good for about 50 days of uptime.
- Of course, the sprintf is only good to 99 hours so that's a bit less time.
- */
-char *ICHIPWIFI::getTimeRunning() {
- uint32_t ms = millis();
- int seconds = (int) (ms / 1000) % 60;
- int minutes = (int) ((ms / (1000 * 60)) % 60);
- int hours = (int) ((ms / (1000 * 3600)) % 24);
- sprintf(buffer, "%02d:%02d:%02d", hours, minutes, seconds);
- return buffer;
-}
-
-/*
- * Handle a message sent by the DeviceManager.
- * Currently MSG_SET_PARAM is supported. The message should be a two element char pointer array
- * containing the addresses of a two element char array. char *paramPtr[2] = { ¶m[0][0], ¶m[1][0] };
- * Element 0 of the base array (char param [2][20]; )should contain the name of the parameter to be changed
- * Element 1 of the base array should contain the new value to be set.
- *
- * sendMessage(DEVICE_WIFI, ICHIP2128, MSG_SET_PARAM, paramPtr);
- *
- */
-void ICHIPWIFI::handleMessage(uint32_t messageType, void* message) {
- Device::handleMessage(messageType, message); //Only matters if message is MSG_STARTUP
-
- switch (messageType) {
-
- case MSG_SET_PARAM:{ //Sets a single parameter to a single value
- char **params = (char **)message; //recast message as a two element array (params)
- // Logger::console("Received Device: %s value %s",params[0], params[1]);
- setParam((char *)params[0], (char *)params[1]);
- break;
- }
- case MSG_CONFIG_CHANGE:{ //Loads all parameters to web site
- loadParameters();
- break;
- }
- case MSG_COMMAND: //Sends a message to the WiReach module in the form of AT+imessage
- sendCmd((char *)message);
- break;
- }
-
-}
-
-/*
- * Determine if a parameter has changed
- * The result will be processed in loop() -> processParameterChange()
- */
-void ICHIPWIFI::getNextParam() {
- sendCmd("WNXT", GET_PARAM); //send command to get next changed parameter
-}
-
-/*
- * Try to retrieve the value of the given parameter.
- */
-void ICHIPWIFI::getParamById(String paramName) {
- sendCmd(paramName + "?", GET_PARAM);
-}
-
-/*
- * Set a parameter to the given string value
- */
-void ICHIPWIFI::setParam(String paramName, String value) {
- sendCmd(paramName + "=\"" + value + "\"", SET_PARAM);
-}
-
-/*
- * Set a parameter to the given int32 value
- */
-void ICHIPWIFI::setParam(String paramName, int32_t value) {
- sprintf(buffer, "%l", value);
- setParam(paramName, buffer);
-}
-
-/*
- * Set a parameter to the given uint32 value
- */
-void ICHIPWIFI::setParam(String paramName, uint32_t value) {
- sprintf(buffer, "%lu", value);
- setParam(paramName, buffer);
-}
-
-/*
- * Set a parameter to the given sint16 value
- */
-void ICHIPWIFI::setParam(String paramName, int16_t value) {
- sprintf(buffer, "%d", value);
- setParam(paramName, buffer);
-}
-
-/*
- * Set a parameter to the given uint16 value
- */
-void ICHIPWIFI::setParam(String paramName, uint16_t value) {
- sprintf(buffer, "%d", value);
- setParam(paramName, buffer);
-}
-
-/*
- * Set a parameter to the given uint8 value
- */
-void ICHIPWIFI::setParam(String paramName, uint8_t value) {
- sprintf(buffer, "%d", value);
- setParam(paramName, buffer);
-}
-/*
- * Set a parameter to the given float value
- */
-void ICHIPWIFI::setParam(String paramName, float value, int precision) {
- char format[10];
- sprintf(format, "%%.%df", precision);
- sprintf(buffer, format, value);
- setParam(paramName, buffer);
-}
-
-/*
- * Called in the main loop (hopefully) in order to process serial input waiting for us
- * from the wifi module. It should always terminate its answers with 13 so buffer
- * until we get 13 (CR) and then process it.
- *
- */
-
-void ICHIPWIFI::loop() {
- int incoming;
- char buff[6];
- while (serialInterface->available()) {
- incoming = serialInterface->read();
- if (incoming != -1) { //and there is no reason it should be -1
- if (incoming == 13 || ibWritePtr > 126) { // on CR or full buffer, process the line
- incomingBuffer[ibWritePtr] = 0; //null terminate the string
- ibWritePtr = 0; //reset the write pointer
- //what we do with the input depends on what state the ICHIP comm was set to.
- if (Logger::isDebug()) {
- sprintf(buff, "%u", state);
- String temp = "In Data, state: " + String(buff);
- Logger::debug(ICHIP2128, (char *)temp.c_str());
- temp = "Data from ichip: " + String(incomingBuffer);
- Logger::debug(ICHIP2128, (char *)temp.c_str());
-
- }
-
- //The ichip echoes our commands back at us. The safer option might be to verify that the command
- //we think we're about to process is really proper by validating the echo here. But, for now
- //just ignore echoes.
- if (strncmp(incomingBuffer, Constants::ichipCommandPrefix, 4) != 0) {
- switch (state) {
- case GET_PARAM: //reply from an attempt to read changed parameters from ichip
- if (strchr(incomingBuffer, '='))
- processParameterChange(incomingBuffer);
- break;
- case SET_PARAM: //reply from sending parameters to the ichip
- break;
- case START_TCP_LISTENER: //reply from turning on a listening socket
- //reply hopefully has the listening socket #.
- if (strcmp(incomingBuffer, Constants::ichipErrorString)) {
- listeningSocket = atoi(&incomingBuffer[2]);
- if (listeningSocket < 10) listeningSocket = 0;
- if (listeningSocket > 11) listeningSocket = 0;
- if (Logger::isDebug()) {
- sprintf(buff, "%u", listeningSocket);
- Logger::debug(ICHIP2128, buff);
- }
- }
- break;
- case GET_ACTIVE_SOCKETS: //reply from asking for active connections
- if (strcmp(incomingBuffer, Constants::ichipErrorString)) {
- activeSockets[0] = atoi(strtok(&incomingBuffer[3], ","));
- activeSockets[1] = atoi(strtok(NULL, ","));
- activeSockets[2] = atoi(strtok(NULL, ","));
- activeSockets[3] = atoi(strtok(NULL, ","));
- if (Logger::isDebug()) {
- sprintf(buff, "%i", activeSockets[0]);
- Logger::debug(ICHIP2128, buff);
- sprintf(buff, "%i", activeSockets[1]);
- Logger::debug(ICHIP2128, buff);
- sprintf(buff, "%i", activeSockets[2]);
- Logger::debug(ICHIP2128, buff);
- sprintf(buff, "%i", activeSockets[3]);
- Logger::debug(ICHIP2128, buff);
- }
- }
- break;
- case POLL_SOCKET: //reply from asking about state of socket and how much data it has
-
- break;
- case SEND_SOCKET: //reply from sending data over a socket
- break;
- case GET_SOCKET: //reply requesting the data pending on a socket
- //reply is I/:data
- int dLen;
- //do not do anything if the socket read returned an error.
- if (strstr(incomingBuffer, "ERROR") == NULL) {
- if (strcmp(incomingBuffer, Constants::ichipErrorString)) {
- dLen = atoi( strtok(&incomingBuffer[2], ":") );
- String datastr = strtok(0, ":"); //get the rest of the string
- datastr.toLowerCase();
- String ret = elmProc->processELMCmd((char *)datastr.c_str());
- sendToSocket(0, ret); //TODO: need to actually track which socket requested this data
- }
- }
- break;
- case IDLE: //not sure whether to leave this info or go to debug. The ichip shouldn't be sending things in idle state
- default:
- //Logger::info(ICHIP2128, incomingBuffer);
- break;
-
- }
-
- //if we got an I/ reply then the command is done sending data. So, see if there is a buffered cmd to send.
- if (strstr(incomingBuffer, "I/") != NULL) {
- state = IDLE;
- if (psReadPtr != psWritePtr) { //if there is a parameter to send then do it
- String temp = "Sending buffered cmd: " + sendingBuffer[psReadPtr].cmd;
- if (Logger::isDebug()) Logger::debug(ICHIP2128, (char *)temp.c_str());
- sendCmd(sendingBuffer[psReadPtr].cmd, sendingBuffer[psReadPtr].state);
- psReadPtr = (psReadPtr + 1) & 63;
- }
- }
- }
- } else { // add more characters
- if (incoming != 10) // don't add a LF character
- incomingBuffer[ibWritePtr++] = (char) incoming;
- }
- }
- else return;
- }
-
- if (millis() > lastSentTime + 1000) { //if the last sent command hasn't gotten a reply in 1 second
- state = IDLE; //something went wrong so reset state
- //sendCmd(lastSentCmd, lastSentState); //try to resend it
- //The sendCmd call resets lastSentTime so this will at most be called every second until the iChip interface decides to cooperate.
- }
-}
-
-/*
- * Process the parameter update from ichip we received as a response to AT+iWNXT.
- * The response usually looks like this : key="value", so the key can be isolated
- * by looking for the '=' sign and the leading/trailing '"' have to be ignored.
- */
-void ICHIPWIFI::processParameterChange(char *key) {
- PotThrottleConfiguration *acceleratorConfig = NULL;
- PotThrottleConfiguration *brakeConfig = NULL;
- MotorControllerConfiguration *motorConfig = NULL;
- bool parameterFound = true;
-
- char *value = strchr(key, '=');
- if (!value)
- return;
-
- Throttle *accelerator = DeviceManager::getInstance()->getAccelerator();
- Throttle *brake = DeviceManager::getInstance()->getBrake();
- MotorController *motorController = DeviceManager::getInstance()->getMotorController();
-
- if (accelerator)
- acceleratorConfig = (PotThrottleConfiguration *)accelerator->getConfiguration();
- if (brake)
- brakeConfig = (PotThrottleConfiguration *)brake->getConfiguration();
- if(motorController)
- motorConfig = (MotorControllerConfiguration *)motorController->getConfiguration();
-
- value[0] = 0; // replace the '=' sign with a 0
- value++;
- if (value[0] == '"')
- value++; // if the value starts with a '"', advance one character
- if (value[strlen(value) - 1] == '"')
- value[strlen(value) - 1] = 0; // if the value ends with a '"' character, replace it with 0
-
- if (!strcmp(key, Constants::numThrottlePots) && acceleratorConfig) {
- acceleratorConfig->numberPotMeters = atol(value);
- accelerator->saveConfiguration();
- } else if (!strcmp(key, Constants::throttleSubType) && acceleratorConfig) {
- acceleratorConfig->throttleSubType = atol(value);
- accelerator->saveConfiguration();
- } else if (!strcmp(key, Constants::throttleMin1) && acceleratorConfig) {
- acceleratorConfig->minimumLevel1 = atol(value);
- accelerator->saveConfiguration();
- } else if (!strcmp(key, Constants::throttleMin2) && acceleratorConfig) {
- acceleratorConfig->minimumLevel2 = atol(value);
- accelerator->saveConfiguration();
- } else if (!strcmp(key, Constants::throttleMax1) && acceleratorConfig) {
- acceleratorConfig->maximumLevel1 = atol(value);
- accelerator->saveConfiguration();
- } else if (!strcmp(key, Constants::throttleMax2) && acceleratorConfig) {
- acceleratorConfig->maximumLevel2 = atol(value);
- accelerator->saveConfiguration();
- } else if (!strcmp(key, Constants::throttleRegenMax) && acceleratorConfig) {
- acceleratorConfig->positionRegenMaximum = atol(value) * 10;
- } else if (!strcmp(key, Constants::throttleRegenMin) && acceleratorConfig) {
- acceleratorConfig->positionRegenMinimum = atol(value) * 10;
- accelerator->saveConfiguration();
- } else if (!strcmp(key, Constants::throttleFwd) && acceleratorConfig) {
- acceleratorConfig->positionForwardMotionStart = atol(value) * 10;
- accelerator->saveConfiguration();
- } else if (!strcmp(key, Constants::throttleMap) && acceleratorConfig) {
- acceleratorConfig->positionHalfPower = atol(value) * 10;
- accelerator->saveConfiguration();
- } else if (!strcmp(key, Constants::throttleMinRegen) && acceleratorConfig) {
- acceleratorConfig->minimumRegen = atol(value);
- accelerator->saveConfiguration();
- } else if (!strcmp(key, Constants::throttleMaxRegen) && acceleratorConfig) {
- acceleratorConfig->maximumRegen = atol(value);
- accelerator->saveConfiguration();
- } else if (!strcmp(key, Constants::throttleCreep) && acceleratorConfig) {
- acceleratorConfig->creep = atol(value);
- accelerator->saveConfiguration();
- } else if (!strcmp(key, Constants::brakeMin) && brakeConfig) {
- brakeConfig->minimumLevel1 = atol(value);
- brake->saveConfiguration();
- } else if (!strcmp(key, Constants::brakeMax) && brakeConfig) {
- brakeConfig->maximumLevel1 = atol(value);
- brake->saveConfiguration();
- } else if (!strcmp(key, Constants::brakeMinRegen) && brakeConfig) {
- brakeConfig->minimumRegen = atol(value);
- brake->saveConfiguration();
- } else if (!strcmp(key, Constants::brakeMaxRegen) && brakeConfig) {
- brakeConfig->maximumRegen = atol(value);
- brake->saveConfiguration();
- } else if (!strcmp(key, Constants::speedMax) && motorConfig) {
- motorConfig->speedMax = atol(value);
- motorController->saveConfiguration();
- } else if (!strcmp(key, Constants::torqueMax) && motorConfig) {
- motorConfig->torqueMax = atol(value) * 10;
- motorController->saveConfiguration();
- } else if (!strcmp(key, Constants::coolFan) && motorConfig) {
- motorConfig->coolFan = atol(value);
- motorController->saveConfiguration();
- } else if (!strcmp(key, Constants::coolOn) && motorConfig) {
- motorConfig->coolOn = (atol(value));
- motorController->saveConfiguration();
- } else if (!strcmp(key, Constants::coolOff) && motorConfig) {
- motorConfig->coolOff = (atol(value));
- motorController->saveConfiguration();
- } else if (!strcmp(key, Constants::prechargeR) && motorConfig) {
- motorConfig->prechargeR = atol(value);
- motorController->saveConfiguration();
- } else if (!strcmp(key, Constants::prechargeRelay) && motorConfig) {
- motorConfig->prechargeRelay = atol(value);
- motorController->saveConfiguration();
- } else if (!strcmp(key, Constants::nominalVolt) && motorConfig) {
- motorConfig->nominalVolt = (atol(value))*10;
- motorController->saveConfiguration();
-
- } else if (!strcmp(key, Constants::mainContactorRelay) && motorConfig) {
- motorConfig->mainContactorRelay = atol(value);
- motorController->saveConfiguration();
- } else if (!strcmp(key, Constants::brakeLight) && motorConfig) {
- motorConfig->brakeLight = atol(value);
- motorController->saveConfiguration();
- } else if (!strcmp(key, Constants::revLight) && motorConfig) {
- motorConfig->revLight = atol(value);
- motorController->saveConfiguration();
- } else if (!strcmp(key, Constants::enableIn) && motorConfig) {
- motorConfig->enableIn = atol(value);
- motorController->saveConfiguration();
- } else if (!strcmp(key, Constants::reverseIn) && motorConfig) {
- motorConfig->reverseIn = atol(value);
- motorController->saveConfiguration();
- /* } else if (!strcmp(key, Constants::motorMode) && motorConfig) {
- motorConfig->motorMode = (MotorController::PowerMode)atoi(value);
- motorController->saveConfiguration();
- */
-
-
-
- } else if (!strcmp(key, "x1000")){
- if (255==atol(value)){sysPrefs->setDeviceStatus(strtol(key+1, 0, 16),true);}
- else {sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), false);}
- sysPrefs->forceCacheWrite();
- // Logger::console("Setting Device: %s ID:%X value %X",key, strtol(key+1, 0, 16),atol(value));
-
- } else if (!strcmp(key, "x1001")){
- if (255==atol(value)){sysPrefs->setDeviceStatus(strtol(key+1, 0, 16),true);}
- else {sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), false);}
- sysPrefs->forceCacheWrite();
- } else if (!strcmp(key, "x1002")){
- if (255==atol(value)){sysPrefs->setDeviceStatus(strtol(key+1, 0, 16),true);}
- else {sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), false);}
- sysPrefs->forceCacheWrite();
- } else if (!strcmp(key, "x1031")){
- if (255==atol(value)){sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), true);}
- else {sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), false);}
- sysPrefs->forceCacheWrite();
- } else if (!strcmp(key, "x1032")){
- if (255==atol(value)){sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), true);}
- else {sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), false);}
- sysPrefs->forceCacheWrite();
- } else if (!strcmp(key, "x1033")){
- if (255==atol(value)){sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), true);}
- else {sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), false);}
- sysPrefs->forceCacheWrite();
- } else if (!strcmp(key, "x1034")){
- if (255==atol(value)){sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), true);}
- else {sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), false);}
- sysPrefs->forceCacheWrite();
- } else if (!strcmp(key, "x1010")){
- if (255==atol(value)){sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), true);}
- else {sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), false);}
- sysPrefs->forceCacheWrite();
- } else if (!strcmp(key, "x1020")){
- if (255==atol(value)){sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), true);}
- else {sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), false);}
- sysPrefs->forceCacheWrite();
- } else if (!strcmp(key, "x1040")){
- if (255==atol(value)){sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), true);}
- else {sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), false);}
- sysPrefs->forceCacheWrite();
- } else if (!strcmp(key, "x2000")){
- if (255==atol(value)){sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), true);}
- else {sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), false);}
- sysPrefs->forceCacheWrite();
- } else if (!strcmp(key, "x6000")){
- if (255==atol(value)){sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), true);}
- else {sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), false);}
- sysPrefs->forceCacheWrite();
- } else if (!strcmp(key, "x6500")){
- if (255==atol(value)){sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), true);}
- else {sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), false);}
- sysPrefs->forceCacheWrite();
-
- } else if (!strcmp(key, Constants::logLevel)) {
- extern PrefHandler *sysPrefs;
- uint8_t loglevel = atoi(value);
- Logger::setLoglevel((Logger::LogLevel)loglevel);
- sysPrefs->write(EESYS_LOG_LEVEL, loglevel);
- } else {
- parameterFound = false;
- }
- if (parameterFound) {
- Logger::info(ICHIP2128, "parameter change: %s", key);
- getNextParam(); // try to get another one immediately
- }
-}
-
-/*
- * Get parameters from devices and forward them to ichip.
- * This is required to initially set-up the ichip
- */
-void ICHIPWIFI::loadParameters() {
- MotorController *motorController = DeviceManager::getInstance()->getMotorController();
- Throttle *accelerator = DeviceManager::getInstance()->getAccelerator();
- Throttle *brake = DeviceManager::getInstance()->getBrake();
- PotThrottleConfiguration *acceleratorConfig = NULL;
- PotThrottleConfiguration *brakeConfig = NULL;
- MotorControllerConfiguration *motorConfig = NULL;
-
- Logger::info("loading config params to ichip/wifi");
-
- if (accelerator)
- acceleratorConfig = (PotThrottleConfiguration *)accelerator->getConfiguration();
- if (brake)
- brakeConfig = (PotThrottleConfiguration *)brake->getConfiguration();
- if (motorController)
- motorConfig = (MotorControllerConfiguration *)motorController->getConfiguration();
-
- if (acceleratorConfig) {
- setParam(Constants::numThrottlePots, acceleratorConfig->numberPotMeters);
- setParam(Constants::throttleSubType, acceleratorConfig->throttleSubType);
- setParam(Constants::throttleMin1, acceleratorConfig->minimumLevel1);
- setParam(Constants::throttleMin2, acceleratorConfig->minimumLevel2);
- setParam(Constants::throttleMax1, acceleratorConfig->maximumLevel1);
- setParam(Constants::throttleMax2, acceleratorConfig->maximumLevel2);
- setParam(Constants::throttleRegenMax, (uint16_t)(acceleratorConfig->positionRegenMaximum / 10));
- setParam(Constants::throttleRegenMin, (uint16_t)(acceleratorConfig->positionRegenMinimum / 10));
- setParam(Constants::throttleFwd, (uint16_t)(acceleratorConfig->positionForwardMotionStart / 10));
- setParam(Constants::throttleMap, (uint16_t)(acceleratorConfig->positionHalfPower / 10));
- setParam(Constants::throttleMinRegen, acceleratorConfig->minimumRegen);
- setParam(Constants::throttleMaxRegen, acceleratorConfig->maximumRegen);
- setParam(Constants::throttleCreep, acceleratorConfig->creep);
- }
- if (brakeConfig) {
- setParam(Constants::brakeMin, brakeConfig->minimumLevel1);
- setParam(Constants::brakeMax, brakeConfig->maximumLevel1);
- setParam(Constants::brakeMinRegen, brakeConfig->minimumRegen);
- setParam(Constants::brakeMaxRegen, brakeConfig->maximumRegen);
- }
- if (motorConfig) {
- setParam(Constants::speedMax, motorConfig->speedMax);
- setParam(Constants::coolFan, motorConfig->coolFan);
- setParam(Constants::coolOn, motorConfig->coolOn);
- setParam(Constants::coolOff, motorConfig->coolOff);
- setParam(Constants::brakeLight, motorConfig->brakeLight);
- setParam(Constants::revLight, motorConfig->revLight);
- setParam(Constants::enableIn, motorConfig->enableIn);
- setParam(Constants::reverseIn, motorConfig->reverseIn);
- setParam(Constants::prechargeR, motorConfig->prechargeR);
- setParam(Constants::prechargeRelay, motorConfig->prechargeRelay);
- setParam(Constants::mainContactorRelay, motorConfig->mainContactorRelay);
- uint16_t nmvlt = motorConfig->nominalVolt/10;
- setParam(Constants::nominalVolt, nmvlt);
- setParam(Constants::torqueMax, (uint16_t)(motorConfig->torqueMax / 10)); // skip the tenth's
- }
- setParam(Constants::logLevel, (uint8_t)Logger::getLogLevel());
-
-
-}
-
-DeviceType ICHIPWIFI::getType() {
- return DEVICE_WIFI;
-}
-
-DeviceId ICHIPWIFI::getId() {
- return (ICHIP2128);
-}
-
-void ICHIPWIFI::loadConfiguration() {
- WifiConfiguration *config = (WifiConfiguration *)getConfiguration();
-
- if (prefsHandler->checksumValid()) { //checksum is good, read in the values stored in EEPROM
- Logger::debug(ICHIP2128, "Valid checksum so using stored wifi config values");
- //TODO: implement processing of config params for WIFI
-// prefsHandler->read(EESYS_WIFI0_SSID, &config->ssid);
- }
-}
-
-void ICHIPWIFI::saveConfiguration() {
- WifiConfiguration *config = (WifiConfiguration *) getConfiguration();
-
- //TODO: implement processing of config params for WIFI
-// prefsHandler->write(EESYS_WIFI0_SSID, config->ssid);
-// prefsHandler->saveChecksum();
-}
diff --git a/sys_io.cpp b/sys_io.cpp
deleted file mode 100644
index 00487f7..0000000
--- a/sys_io.cpp
+++ /dev/null
@@ -1,394 +0,0 @@
-/*
- * sys_io.cpp
- *
- * Handles the low level details of system I/O
- *
-Copyright (c) 2013 Collin Kidder, Michael Neuweiler, Charles Galpin
-
-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.
-
-some portions based on code credited as:
-Arduino Due ADC->DMA->USB 1MSPS
-by stimmer
-
-*/
-
-#include "sys_io.h"
-
-#undef HID_ENABLED
-
-uint8_t dig[NUM_DIGITAL];
-uint8_t adc[NUM_ANALOG][2];
-uint8_t out[NUM_OUTPUT];
-
-volatile int bufn,obufn;
-volatile uint16_t adc_buf[NUM_ANALOG][256]; // 4 buffers of 256 readings
-uint16_t adc_values[NUM_ANALOG * 2];
-uint16_t adc_out_vals[NUM_ANALOG];
-
-
-
-int NumADCSamples;
-
-//the ADC values fluctuate a lot so smoothing is required.
-uint16_t adc_buffer[NUM_ANALOG][64];
-uint8_t adc_pointer[NUM_ANALOG]; //pointer to next position to use
-
-extern PrefHandler *sysPrefs;
-
-ADC_COMP adc_comp[NUM_ANALOG];
-
-bool useRawADC = false;
-
-//forces the digital I/O ports to a safe state. This is called very early in initialization.
-void sys_early_setup() {
- int i;
-
- //the first order of business is to figure out what hardware we are running on and fill in
- //the pin tables.
-
- uint8_t rawadc;
- sysPrefs->read(EESYS_RAWADC, &rawadc);
- if (rawadc != 0) {
- useRawADC = true;
- Logger::info("Using raw ADC mode");
- }
- else useRawADC = false;
-
- NumADCSamples = 64;
-
- uint8_t sys_type;
- sysPrefs->read(EESYS_SYSTEM_TYPE, &sys_type);
- if (sys_type == 2) {
- Logger::info("Running on GEVCU2/DUED hardware.");
- dig[0]=9; dig[1]=11; dig[2]=12; dig[3]=13;
- adc[0][0] = 1; adc[0][1] = 0;
- adc[1][0] = 3; adc[1][1] = 2;
- adc[2][0] = 5; adc[2][1] = 4;
- adc[3][0] = 7; adc[3][1] = 6;
- out[0] = 52; out[1] = 22; out[2] = 48; out[3] = 32;
- out[4] = 255; out[5] = 255; out[6] = 255; out[7] = 255;
- NumADCSamples = 32;
- } else if (sys_type == 3) {
- Logger::info("Running on GEVCU3 hardware");
- dig[0]=48; dig[1]=49; dig[2]=50; dig[3]=51;
- adc[0][0] = 3; adc[0][1] = 255;
- adc[1][0] = 2; adc[1][1] = 255;
- adc[2][0] = 1; adc[2][1] = 255;
- adc[3][0] = 0; adc[3][1] = 255;
- out[0] = 9; out[1] = 8; out[2] = 7; out[3] = 6;
- out[4] = 255; out[5] = 255; out[6] = 255; out[7] = 255;
- useRawADC = true; //this board does require raw adc so force it.
- } else if (sys_type == 4) {
- Logger::info("Running on GEVCU 4.x hardware");
- dig[0]=48; dig[1]=49; dig[2]=50; dig[3]=51;
- adc[0][0] = 3; adc[0][1] = 255;
- adc[1][0] = 2; adc[1][1] = 255;
- adc[2][0] = 1; adc[2][1] = 255;
- adc[3][0] = 0; adc[3][1] = 255;
- out[0] = 4; out[1] = 5; out[2] = 6; out[3] = 7;
- out[4] = 2; out[5] = 3; out[6] = 8; out[7] = 9;
- useRawADC = true; //this board does require raw adc so force it.
- } else {
- Logger::info("Running on legacy hardware?");
- dig[0]=11; dig[1]=9; dig[2]=13; dig[3]=12;
- adc[0][0] = 1; adc[0][1] = 0;
- adc[1][0] = 2; adc[1][1] = 3;
- adc[2][0] = 4; adc[2][1] = 5;
- adc[3][0] = 7; adc[3][1] = 6;
- out[0] = 52; out[1] = 22; out[2] = 48; out[3] = 32;
- out[4] = 255; out[5] = 255; out[6] = 255; out[7] = 255;
- NumADCSamples = 32;
- }
-
- for (i = 0; i < NUM_DIGITAL; i++) pinMode(dig[i], INPUT);
- for (i = 0; i < NUM_OUTPUT; i++) {
- if (out[i] != 255) {
- pinMode(out[i], OUTPUT);
- digitalWrite(out[i], LOW);
- }
- }
-
-}
-
-/*
-Initialize DMA driven ADC and read in gain/offset for each channel
-*/
-void setup_sys_io() {
- int i;
-
- setupFastADC();
-
- //requires the value to be contiguous in memory
- for (i = 0; i < NUM_ANALOG; i++) {
- sysPrefs->read(EESYS_ADC0_GAIN + 4*i, &adc_comp[i].gain);
- sysPrefs->read(EESYS_ADC0_OFFSET + 4*i, &adc_comp[i].offset);
- //Logger::debug("ADC:%d GAIN: %d Offset: %d", i, adc_comp[i].gain, adc_comp[i].offset);
- for (int j = 0; j < NumADCSamples; j++) adc_buffer[i][j] = 0;
- adc_pointer[i] = 0;
- adc_values[i] = 0;
- adc_out_vals[i] = 0;
- }
-}
-
-/*
-Some of the boards are differential and thus require subtracting one ADC from another to obtain the true value. This function
-handles that case. It also applies gain and offset
-*/
-uint16_t getDiffADC(uint8_t which) {
- uint32_t low, high;
-
- low = adc_values[adc[which][0]];
- high = adc_values[adc[which][1]];
-
- if (low < high) {
-
- //first remove the bias to bring us back to where it rests at zero input volts
-
- if (low >= adc_comp[which].offset) low -= adc_comp[which].offset;
- else low = 0;
- if (high >= adc_comp[which].offset) high -= adc_comp[which].offset;
- else high = 0;
-
- //gain multiplier is 1024 for 1 to 1 gain, less for lower gain, more for higher.
- low *= adc_comp[which].gain;
- low = low >> 10; //divide by 1024 again to correct for gain multiplier
- high *= adc_comp[which].gain;
- high = high >> 10;
-
- //Lastly, the input scheme is basically differential so we have to subtract
- //low from high to get the actual value
- high = high - low;
- }
- else high = 0;
-
- if (high > 4096) high = 0; //if it somehow got wrapped anyway then set it back to zero
-
- return high;
-}
-
-/*
-Exactly like the previous function but for non-differential boards (all the non-prototype boards are non-differential)
-*/
-uint16_t getRawADC(uint8_t which) {
- uint32_t val;
-
- val = adc_values[adc[which][0]];
-
- //first remove the bias to bring us back to where it rests at zero input volts
-
- if (val >= adc_comp[which].offset) val -= adc_comp[which].offset;
- else val = 0;
-
- //gain multiplier is 1024 for 1 to 1 gain, less for lower gain, more for higher.
- val *= adc_comp[which].gain;
- val = val >> 10; //divide by 1024 again to correct for gain multiplier
-
- if (val > 4096) val = 0; //if it somehow got wrapped anyway then set it back to zero
-
- return val;
-}
-
-/*
-Adds a new ADC reading to the buffer for a channel. The buffer is NumADCSamples large (either 32 or 64) and rolling
-*/
-void addNewADCVal(uint8_t which, uint16_t val) {
- adc_buffer[which][adc_pointer[which]] = val;
- adc_pointer[which] = (adc_pointer[which] + 1) % NumADCSamples;
-}
-
-/*
-Take the arithmetic average of the readings in the buffer for each channel. This smooths out the ADC readings
-*/
-uint16_t getADCAvg(uint8_t which) {
- uint32_t sum;
- sum = 0;
- for (int j = 0; j < NumADCSamples; j++) sum += adc_buffer[which][j];
- sum = sum / NumADCSamples;
- return ((uint16_t)sum);
-}
-
-/*
-get value of one of the 4 analog inputs
-Uses a special buffer which has smoothed and corrected ADC values. This call is very fast
-because the actual work is done via DMA and then a separate polled step.
-*/
-uint16_t getAnalog(uint8_t which) {
- uint16_t val;
-
- if (which >= NUM_ANALOG) which = 0;
-
- return adc_out_vals[which];
-}
-
-//get value of one of the 4 digital inputs
-boolean getDigital(uint8_t which) {
- if (which >= NUM_DIGITAL) which = 0;
- return !(digitalRead(dig[which]));
-}
-
-//set output high or not
-void setOutput(uint8_t which, boolean active) {
- if (which >= NUM_OUTPUT) return;
- if (out[which] == 255) return;
- if (active)
- digitalWrite(out[which], HIGH);
- else digitalWrite(out[which], LOW);
-
-
-}
-
-//get current value of output state (high?)
-boolean getOutput(uint8_t which) {
- if (which >= NUM_OUTPUT) return false;
- if (out[which] == 255) return false;
- return digitalRead(out[which]);
-}
-
-
-
-
-/*
-When the ADC reads in the programmed # of readings it will do two things:
-1. It loads the next buffer and buffer size into current buffer and size
-2. It sends this interrupt
-This interrupt then loads the "next" fields with the proper values. This is
-done with a four position buffer. In this way the ADC is constantly sampling
-and this happens virtually for free. It all happens in the background with
-minimal CPU overhead.
-*/
-void ADC_Handler(){ // move DMA pointers to next buffer
- int f=ADC->ADC_ISR;
- if (f & (1<<27)){ //receive counter end of buffer
- bufn=(bufn+1)&3;
- ADC->ADC_RNPR=(uint32_t)adc_buf[bufn];
- ADC->ADC_RNCR=256;
- }
-}
-
-/*
-Setup the system to continuously read the proper ADC channels and use DMA to place the results into RAM
-Testing to find a good batch of settings for how fast to do ADC readings. The relevant areas:
-1. In the adc_init call it is possible to use something other than ADC_FREQ_MAX to slow down the ADC clock
-2. ADC_MR has a clock divisor, start up time, settling time, tracking time, and transfer time. These can be adjusted
-*/
-void setupFastADC(){
- pmc_enable_periph_clk(ID_ADC);
- adc_init(ADC, SystemCoreClock, ADC_FREQ_MAX, ADC_STARTUP_FAST); //just about to change a bunch of these parameters with the next command
-
- /*
- The MCLK is 12MHz on our boards. The ADC can only run 1MHz so the prescaler must be at least 12x.
- The ADC should take Tracking+Transfer for each read when it is set to switch channels with each read
-
- Example:
- 5+7 = 12 clocks per read 1M / 12 = 83333 reads per second. For newer boards there are 4 channels interleaved
- so, for each channel, the readings are 48uS apart. 64 of these readings are averaged together for a total of 3ms
- worth of ADC in each average. This is then averaged with the current value in the ADC buffer that is used for output.
-
- If, for instance, someone wanted to average over 6ms instead then the prescaler could be set to 24x instead.
- */
- ADC->ADC_MR = (1 << 7) //free running
- + (5 << 8) //12x MCLK divider ((This value + 1) * 2) = divisor
- + (1 << 16) //8 periods start up time (0=0clks, 1=8clks, 2=16clks, 3=24, 4=64, 5=80, 6=96, etc)
- + (1 << 20) //settling time (0=3clks, 1=5clks, 2=9clks, 3=17clks)
- + (4 << 24) //tracking time (Value + 1) clocks
- + (2 << 28);//transfer time ((Value * 2) + 3) clocks
-
- if (useRawADC)
- ADC->ADC_CHER=0xF0; //enable A0-A3
- else ADC->ADC_CHER=0xFF; //enable A0-A7
-
- NVIC_EnableIRQ(ADC_IRQn);
- ADC->ADC_IDR=~(1<<27); //dont disable the ADC interrupt for rx end
- ADC->ADC_IER=1<<27; //do enable it
- ADC->ADC_RPR=(uint32_t)adc_buf[0]; // DMA buffer
- ADC->ADC_RCR=256; //# of samples to take
- ADC->ADC_RNPR=(uint32_t)adc_buf[1]; // next DMA buffer
- ADC->ADC_RNCR=256; //# of samples to take
- bufn=obufn=0;
- ADC->ADC_PTCR=1; //enable dma mode
- ADC->ADC_CR=2; //start conversions
-
- Logger::debug("Fast ADC Mode Enabled");
-}
-
-//polls for the end of an adc conversion event. Then processe buffer to extract the averaged
-//value. It takes this value and averages it with the existing value in an 8 position buffer
-//which serves as a super fast place for other code to retrieve ADC values
-// This is only used when RAWADC is not defined
-void sys_io_adc_poll() {
- if (obufn != bufn) {
- uint32_t tempbuff[8] = {0,0,0,0,0,0,0,0}; //make sure its zero'd
-
- //the eight or four enabled adcs are interleaved in the buffer
- //this is a somewhat unrolled for loop with no incrementer. it's odd but it works
- if (useRawADC) {
- for (int i = 0; i < 256;) {
- tempbuff[3] += adc_buf[obufn][i++];
- tempbuff[2] += adc_buf[obufn][i++];
- tempbuff[1] += adc_buf[obufn][i++];
- tempbuff[0] += adc_buf[obufn][i++];
- }
- }
- else {
- for (int i = 0; i < 256;) {
- tempbuff[7] += adc_buf[obufn][i++];
- tempbuff[6] += adc_buf[obufn][i++];
- tempbuff[5] += adc_buf[obufn][i++];
- tempbuff[4] += adc_buf[obufn][i++];
- tempbuff[3] += adc_buf[obufn][i++];
- tempbuff[2] += adc_buf[obufn][i++];
- tempbuff[1] += adc_buf[obufn][i++];
- tempbuff[0] += adc_buf[obufn][i++];
- }
- }
-
- //for (int i = 0; i < 256;i++) Logger::debug("%i - %i", i, adc_buf[obufn][i]);
-
- //now, all of the ADC values are summed over 32/64 readings. So, divide by 32/64 (shift by 5/6) to get the average
- //then add that to the old value we had stored and divide by two to average those. Lots of averaging going on.
- if (useRawADC) {
- for (int j = 0; j < 4; j++) {
- adc_values[j] += (tempbuff[j] >> 6);
- adc_values[j] = adc_values[j] >> 1;
- }
- }
- else {
- for (int j = 0; j < 8; j++) {
- adc_values[j] += (tempbuff[j] >> 5);
- adc_values[j] = adc_values[j] >> 1;
- //Logger::debug("A%i: %i", j, adc_values[j]);
- }
- }
-
- for (int i = 0; i < NUM_ANALOG; i++) {
- int val;
- if (useRawADC) val = getRawADC(i);
- else val = getDiffADC(i);
-// addNewADCVal(i, val);
-// adc_out_vals[i] = getADCAvg(i);
- adc_out_vals[i] = val;
- }
-
- obufn = bufn;
- }
-}
-
-
diff --git a/util/i2128d809b21UAP.imf b/util/i2128d809b21UAP.imf
new file mode 100644
index 0000000..6e3ad92
Binary files /dev/null and b/util/i2128d809b21UAP.imf differ
diff --git a/util/i2128d811d13BCOM.imf b/util/i2128d811d13BCOM.imf
new file mode 100644
index 0000000..7266c8f
Binary files /dev/null and b/util/i2128d811d13BCOM.imf differ
diff --git a/util/i2128d811d13BCOM.imz b/util/i2128d811d13BCOM.imz
new file mode 100644
index 0000000..19be16f
Binary files /dev/null and b/util/i2128d811d13BCOM.imz differ
diff --git a/website/README.txt b/website/README.txt
index 7029443..210259c 100755
--- a/website/README.txt
+++ b/website/README.txt
@@ -16,7 +16,16 @@ Then to update the website after changes,
2. Choose the "Site Pack" tool
3. Browse to the website/src dir, select the index.htm as default
4. Select "C02128" as the platform and click "Pack". At this point the parameters should show.
-5. Select all the parameters, enter 20 for the max length value to fill and click "Fill"
+5. Select all the parameters, enter 30 for the max length value to fill and click "Fill"
6. Click "Save" and point it to website.img
At this point you upload the image to the GEVCU using http://192.168.3.10/ichip and power cycle the GEVCU to have it activated.
+
+
+
+What about the "WEB-INF" folder?
+
+If you are developing the website and want to test it locally with an Apache Tomcat server, just deploy the contents of website/src to
+your webapps directory and copy the WEB-INF folder also there. This way Tomcat recognizes the webapp and also uses a filter to replace
+the placeholders in certain .js files with meaningful data. The WEB-INF folder is deliberately not included in the website/src folder
+because the ichip packaging tool would pick-up all its files too and the website would become bigger than 256kB.
\ No newline at end of file
diff --git a/website/WEB-INF/classes/filters/TextReplaceFilter$ByteOutputStream.class b/website/WEB-INF/classes/filters/TextReplaceFilter$ByteOutputStream.class
new file mode 100644
index 0000000..afcdb49
Binary files /dev/null and b/website/WEB-INF/classes/filters/TextReplaceFilter$ByteOutputStream.class differ
diff --git a/website/WEB-INF/classes/filters/TextReplaceFilter$ByteResponseWrapper.class b/website/WEB-INF/classes/filters/TextReplaceFilter$ByteResponseWrapper.class
new file mode 100644
index 0000000..6230b92
Binary files /dev/null and b/website/WEB-INF/classes/filters/TextReplaceFilter$ByteResponseWrapper.class differ
diff --git a/website/WEB-INF/classes/filters/TextReplaceFilter.class b/website/WEB-INF/classes/filters/TextReplaceFilter.class
new file mode 100644
index 0000000..f95d720
Binary files /dev/null and b/website/WEB-INF/classes/filters/TextReplaceFilter.class differ
diff --git a/website/WEB-INF/classes/filters/TextReplaceFilter.java b/website/WEB-INF/classes/filters/TextReplaceFilter.java
new file mode 100644
index 0000000..544d2f5
--- /dev/null
+++ b/website/WEB-INF/classes/filters/TextReplaceFilter.java
@@ -0,0 +1,113 @@
+package filters;
+
+import java.io.ByteArrayOutputStream;
+import java.io.IOException;
+import java.io.PrintWriter;
+import java.util.ArrayList;
+import java.util.Enumeration;
+
+import javax.servlet.Filter;
+import javax.servlet.FilterChain;
+import javax.servlet.FilterConfig;
+import javax.servlet.ServletException;
+import javax.servlet.ServletOutputStream;
+import javax.servlet.ServletRequest;
+import javax.servlet.ServletResponse;
+import javax.servlet.WriteListener;
+import javax.servlet.http.HttpServletResponse;
+import javax.servlet.http.HttpServletResponseWrapper;
+
+/**
+ * A filter to replace place-holders in a serviced resource with configured
+ * values
+ *
+ * @author Michael Neuweiler
+ *
+ */
+public class TextReplaceFilter implements Filter {
+
+ private String[] replaceFrom = new String[0];
+ private String[] replaceTo = new String[0];
+
+ @Override
+ public void destroy() {
+ replaceFrom = new String[0];
+ replaceTo = new String[0];
+ }
+
+ @Override
+ public void doFilter(ServletRequest request, ServletResponse response, FilterChain chain)
+ throws IOException, ServletException {
+ ByteResponseWrapper wrapper = new ByteResponseWrapper((HttpServletResponse) response);
+ chain.doFilter(request, wrapper);
+ String out = new String(wrapper.getBytes());
+ for (int i = 0; i < replaceFrom.length; i++) {
+ out = out.replaceAll(replaceFrom[i], replaceTo[i]);
+ }
+ response.setContentLength(out.length());
+ response.getWriter().print(out);
+ }
+
+ @Override
+ public void init(FilterConfig filterConfig) throws ServletException {
+ Enumeration e = filterConfig.getInitParameterNames();
+ ArrayList params = new ArrayList<>();
+ ArrayList values = new ArrayList<>();
+ while (e.hasMoreElements()) {
+ String param = e.nextElement();
+ params.add(param);
+ values.add(filterConfig.getInitParameter(param));
+ }
+ replaceFrom = params.toArray(new String[0]);
+ replaceTo = values.toArray(new String[0]);
+ }
+
+ static class ByteResponseWrapper extends HttpServletResponseWrapper {
+ private PrintWriter writer;
+ private ByteOutputStream output;
+
+ public byte[] getBytes() {
+ writer.flush();
+ return output.getBytes();
+ }
+
+ public ByteResponseWrapper(HttpServletResponse response) {
+ super(response);
+ output = new ByteOutputStream();
+ writer = new PrintWriter(output);
+ }
+
+ @Override
+ public PrintWriter getWriter() {
+ return writer;
+ }
+
+ @Override
+ public ServletOutputStream getOutputStream() throws IOException {
+ return output;
+ }
+ }
+
+ static class ByteOutputStream extends ServletOutputStream {
+ private ByteArrayOutputStream bos = new ByteArrayOutputStream();
+
+ @Override
+ public void write(int b) throws IOException {
+ bos.write(b);
+ }
+
+ @Override
+ public boolean isReady() {
+ return false;
+ }
+
+ @Override
+ public void setWriteListener(WriteListener arg0) {
+ }
+
+ public byte[] getBytes() {
+ return bos.toByteArray();
+ }
+ }
+
+}
diff --git a/website/WEB-INF/web.xml b/website/WEB-INF/web.xml
new file mode 100644
index 0000000..d1a8009
--- /dev/null
+++ b/website/WEB-INF/web.xml
@@ -0,0 +1,143 @@
+
+
+
+ GEVCU
+ GEVCU Website with fake data
+
+
+ TextReplaceFilter
+ filters.TextReplaceFilter
+
+ ~numberPotMeters~2
+ ~throttleSubType~1
+ ~minimumLevel~111
+ ~minimumLevel2~222
+ ~maximumLevel~3333
+ ~maximumLevel2~4000
+ ~positionRegenMaximum~10
+ ~positionRegenMinimum~20
+ ~positionForwardStart~30
+ ~positionHalfPower~80
+ ~minimumRegen~5
+ ~maximumRegen~80
+ ~creepLevel~10
+ ~creepSpeed~700
+ ~brakeMinimumLevel~11
+ ~brakeMaximumLevel~4001
+ ~brakeMinimumRegen~20
+ ~brakeMaximumRegen~100
+ ~brakeHold~50
+ ~cruiseUseRpm~1
+ ~cruiseSpeedStep~300
+ ~cruiseSpeedSet~1800,3035,4800,3050,3700
+
+ ~speedMax~7000
+ ~torqueMax~220
+ ~motorMode~1
+ ~nominalVolt~399
+ ~invertDirection~1
+ ~slewRateMotor~100
+ ~slewRateRegen~10
+
+ ~maxMechPowerMotor~110
+ ~maxMechPowerRegen~109
+ ~dcVoltLimitMotor~300
+ ~dcVoltLimitRegen~410
+ ~dcCurrentLimitMotor~300
+ ~dcCurrentLimitRegen~200
+ ~enableOscLimiter~1
+
+
+ ~torqueRange~-220,220
+ ~rpmRange~0,8000
+ ~currentRange~-200,200
+ ~motorTempRange~0,90,120
+ ~controllerTempRange~0,60,80
+ ~batteryRangeLow~297,357,368
+ ~batteryRangeHigh~387,405,418
+ ~socRange~0,20,100
+ ~powerRange~-150,150
+ ~chargeInputLevels~5, 6, 7, 8, 9, 10, 13, 16, 24, 32, 40, 45, 50
+ ~maximumSolarCurrent~-
+
+
+ ~x1000~1
+ ~x1001~1
+ ~x1002~1
+ ~x1010~1
+ ~x1020~1
+ ~x1022~1
+ ~x1031~1
+ ~x1032~1
+ ~x1033~1
+ ~x1034~0
+ ~x1040~1
+ ~x2000~0
+ ~x3000~1
+ ~x5001~0
+ ~x5003~1
+ ~x6000~0
+ ~x6500~1
+ ~logLevel~2
+
+
+ ~absInput~3
+ ~enableInput~0
+ ~reverseInput~2
+ ~chargePwrAvailInput~1
+ ~interlockInput~255
+
+
+ ~prechargeMillis~1500
+ ~prechargeRelayOutput~1
+ ~mainContactorOutput~0
+ ~secondaryContOutput~2
+ ~fastChargeContOutput~3
+ ~enableMotorOutput~4
+ ~enableChargerOutput~5
+ ~enableDcDcOutput~6
+ ~enableHeaterOutput~7
+ ~heaterValveOutput~255
+ ~heaterPumpOutput~255
+ ~coolingPumpOutput~255
+ ~coolingFanOutput~255
+ ~coolingTempOn~50
+ ~coolingTempOff~40
+ ~brakeLightOutput~255
+ ~reverseLightOutput~255
+ ~warningOutput~255
+ ~powerLimitOutput~255
+
+
+ ~dcDcMode~0
+ ~lowVoltageCommand~13.5
+ ~hvUndervoltageLimit~270
+ ~lvBuckCurrentLimit~150
+ ~hvBuckCurrentLimit~20
+ ~highVoltageCommand~400
+ ~lvUndervoltageLimit~11.5
+ ~lvBoostCurrentLimit~150
+ ~hvBoostCurrentLimit~20
+
+
+ ~maximumInputCurrent~32
+ ~constantCurrent~10
+ ~constantVoltage~416.3
+ ~terminateCurrent~4
+ ~minBatteryVoltage~270
+ ~maxBatteryVoltage~420
+ ~minimumTemperature~5
+ ~maximumTemperature~60
+ ~maximumAmpereHours~100
+ ~maximumChargeTime~600
+ ~deratingRate~10
+ ~deratingReferenceTmp~50
+ ~hystereseStopTemp~60
+ ~hystereseResumeTemp~40
+
+
+
+ TextReplaceFilter
+ *.js
+
+
diff --git a/website/htmlcompressor-1.5.3.jar b/website/htmlcompressor-1.5.3.jar
new file mode 100644
index 0000000..2a6196f
Binary files /dev/null and b/website/htmlcompressor-1.5.3.jar differ
diff --git a/website/minify.sh b/website/minify.sh
new file mode 100644
index 0000000..2bbb0a9
--- /dev/null
+++ b/website/minify.sh
@@ -0,0 +1,7 @@
+rm -rf minified
+java -jar htmlcompressor-1.5.3.jar --remove-intertag-spaces -o minified/ src/*.htm
+cp -R src/config src/fonts src/pics src/sound src/styles src/util src/worker src/*.js minified
+java -jar yuicompressor-2.4.8.jar --nomunge --preserve-semi --disable-optimizations -o '.css$:.css' minified/styles/*.css
+java -jar yuicompressor-2.4.8.jar -o '.js$:.js' minified/util/*.js
+java -jar yuicompressor-2.4.8.jar -o '.js$:.js' minified/worker/*.js
+java -jar yuicompressor-2.4.8.jar -o '.js$:.js' minified/*.js
diff --git a/website/src/.gitignore b/website/src/.gitignore
new file mode 100644
index 0000000..08922f1
--- /dev/null
+++ b/website/src/.gitignore
@@ -0,0 +1 @@
+/WEB-INF/
diff --git a/website/src/about.htm b/website/src/about.htm
index 63df815..8079569 100644
--- a/website/src/about.htm
+++ b/website/src/about.htm
@@ -1,40 +1,32 @@
-
ABOUT GEVCU 5.200
+
ABOUT GEVCU
The Generalized Electric Vehicle Control Unit - GEVCU is an open source
software and hardware project to develop a Vehicle Control Unit (VCU) specifically
-for electric vehicles.
-
-The purpose of GEVCU is to handle throttle control, regenerative
+for electric vehicles. The purpose of GEVCU is to handle throttle control, regenerative
braking, forward, reverse, and such peculiarities as precharge, cooling system control,
instrumentation etc. - essentially the driver interface of the car.
-
GEVCU then manages torque and speed commands to the power electronics
via CAN bus to actually operate the vehicle in response to driver input.
-
But it also provides outputs to instrumentation, brake lights, reverse lights, cooling systems, and other controls specific to that vehicle.
GEVCU is both open-source and object-oriented allowing easy addition of
additional C++ object modules to incorporate multiple standard power components.
It is easily modified using the Arduino IDE to incorporate additional features
peculiar to any specific electric car conversion or build.
-
For most operations, it is easily configurable by non-programmers through
simple web and serial port interfaces to adapt to a wide variety of power
components and vehicle applications.
-GEVCU was originally conceived of and proposed by Jack Rickard of
-Electric Vehicle Television (http://EVtv.me) who wrote the original
+The initial source of the program was developed and is maintained by Collin Kidder
+and provided at GitHub. Major contributors are
+Michael Neuweiler, Charles Galpin and Jack Rickard.
+The hardware was designed and developed by Ed Clausen and Paulo Jorge Pires de Almeida
+based on the Arduino Due. GEVCU was originally conceived of and proposed by Jack Rickard of
+Electric Vehicle Television who wrote the original
design specification.
-The main source of the program was developed and is maintained by Collin Kidder
-and the latest version is always available at http:/github.com/collin80/GEVCU.
-A list of major contributors to the project is maintained there.
-
-Hardware was designed and developed by Ed Clausen and Paulo Jorge Pires de Almeida
-based on the Arduino Due.
-
GEVCU is open source hardware and software and is presented as EXPERIMENTAL - USE AT YOUR
OWN RISK. It is offered strictly for experimental and educational
purposes and is NOT intended for actual use in any commercial product
diff --git a/website/src/annunciator.htm b/website/src/annunciator.htm
old mode 100755
new mode 100644
index 76c1110..5461eab
--- a/website/src/annunciator.htm
+++ b/website/src/annunciator.htm
@@ -1,36 +1,67 @@
+