diff --git a/inc/sp140/battery/BatteryData.h b/inc/sp140/battery/BatteryData.h new file mode 100644 index 00000000..667fdb87 --- /dev/null +++ b/inc/sp140/battery/BatteryData.h @@ -0,0 +1,11 @@ +#ifndef BATTERY_DATA_H +#define BATTERY_DATA_H + +typedef struct { + +float watts; +float wattHoursUsed; + +} BatteryData; + +#endif \ No newline at end of file diff --git a/inc/sp140/display.h b/inc/sp140/display.h index c99b92b0..d3916e35 100644 --- a/inc/sp140/display.h +++ b/inc/sp140/display.h @@ -13,6 +13,7 @@ #include #include "utilities.h" +#include "../../inc/sp140/battery/BatteryData.h" // Library config #define NO_ADAFRUIT_SSD1306_COLOR_COMPATIBILITY @@ -58,9 +59,6 @@ struct UIColors { uint16_t ui_accent; }; -extern float watts; -extern float wattHoursUsed; - // Set up the display and show splash screen void setupDisplay(const STR_DEVICE_DATA_140_V1& deviceData, const HardwareConfig& board_config); @@ -70,7 +68,8 @@ void displayMeta(const STR_DEVICE_DATA_140_V1& deviceData, int duration = 1500); void resetRotation(unsigned int orientation); // Show data on screen -void updateDisplay(const STR_DEVICE_DATA_140_V1& deviceData, +void updateDisplay(BatteryData& batteryData, + const STR_DEVICE_DATA_140_V1& deviceData, const STR_ESC_TELEMETRY_140& escTelemetry, float altitude, bool armed, bool cruising, unsigned int armedStartMillis); diff --git a/inc/sp140/esc.h b/inc/sp140/esc.h deleted file mode 100644 index 32164f54..00000000 --- a/inc/sp140/esc.h +++ /dev/null @@ -1,30 +0,0 @@ -#ifndef INC_SP140_ESC_H_ -#define INC_SP140_ESC_H_ - -#include -#include "sp140/structs.h" - -#ifdef M0_PIO - #include "../../inc/sp140/m0-config.h" -#else - #include "../../inc/sp140/rp2040-config.h" -#endif - -// ESC communication parameters -#define ESC_BAUD_RATE 115200 -#define ESC_DATA_V2_SIZE 22 -#define READ_INTERVAL 0 -#define ESC_TIMEOUT 15 - -void initESC(int escPin); -void setupESCSerial(); -void setESCThrottle(int throttlePWM); -void readESCTelemetry(); -void handleESCSerialData(byte buffer[]); -void prepareESCSerialRead(); -int checkFletcher16(byte byteBuffer[]); - -// External declaration of telemetry data structure -extern STR_ESC_TELEMETRY_140 escTelemetryData; - -#endif // INC_SP140_ESC_H_ diff --git a/inc/sp140/esc/EscBase.h b/inc/sp140/esc/EscBase.h new file mode 100644 index 00000000..f8e6b749 --- /dev/null +++ b/inc/sp140/esc/EscBase.h @@ -0,0 +1,22 @@ +#ifndef ESC_BASE_H +#define ESC_BASE_H + +#include +#include "sp140/structs.h" +#include "EscData.h" + +class EscBase { + +public: + virtual void initESC(int escPin) = 0; + virtual void setupESCSerial() = 0; + virtual void setESCThrottle(int throttlePWM) = 0; + virtual void readESCTelemetry(BatteryData& batteryData, EscData& escData) = 0; + virtual void handleESCSerialData(BatteryData& batteryData, EscData& escData, byte buffer[]) = 0; + virtual void prepareESCSerialRead() = 0; + virtual int checkFletcher16(byte byteBuffer[]) = 0; +}; + + + +#endif \ No newline at end of file diff --git a/inc/sp140/esc/EscData.h b/inc/sp140/esc/EscData.h new file mode 100644 index 00000000..285b39a7 --- /dev/null +++ b/inc/sp140/esc/EscData.h @@ -0,0 +1,15 @@ +#ifndef ESC_DATA_H +#define ESC_DATA_H + +#include +#include "sp140/structs.h" + + +typedef struct { + +STR_ESC_TELEMETRY_140 escTelemetryData; +telem_esc_t raw_esc_telemdata; + +} EscData; + +#endif \ No newline at end of file diff --git a/inc/sp140/esc/FactoryEsc.h b/inc/sp140/esc/FactoryEsc.h new file mode 100644 index 00000000..38714551 --- /dev/null +++ b/inc/sp140/esc/FactoryEsc.h @@ -0,0 +1,35 @@ +#ifndef FACTORY_ESC_H +#define FACTORY_ESC_H + +#include +#include +#include "EscBase.h" +#include "EscData.h" + +// ESC communication parameters +#define ESC_BAUD_RATE 115200 +#define ESC_DATA_V2_SIZE 22 +#define READ_INTERVAL 0 +#define ESC_TIMEOUT 15 + +class FactoryEsc : public EscBase { +public: + static void printRawSentence(byte buffer[]); + + FactoryEsc(CircularBuffer* pVoltageBuffer); + + virtual void initESC(int escPin); + virtual void setupESCSerial(); + virtual void setESCThrottle(int throttlePWM); + virtual void readESCTelemetry(BatteryData& batteryData, EscData& escData); + virtual void handleESCSerialData(BatteryData& batteryData, EscData& escData, byte buffer[]); + virtual void prepareESCSerialRead(); + virtual int checkFletcher16(byte byteBuffer[]); +private: + + Servo esc; + CircularBuffer* pVoltageBuffer; +}; + + +#endif \ No newline at end of file diff --git a/inc/sp140/globals.h b/inc/sp140/globals.h index 4e1bcd4a..24d385b6 100644 --- a/inc/sp140/globals.h +++ b/inc/sp140/globals.h @@ -9,11 +9,6 @@ extern unsigned long cruisedAtMillis; extern int prevPotLvl; extern int cruisedPotVal; -extern float watts; -extern float wattHoursUsed; - extern STR_DEVICE_DATA_140_V1 deviceData; -extern STR_ESC_TELEMETRY_140 escTelemetryData; - #endif // INC_SP140_GLOBALS_H_ diff --git a/inc/sp140/rp2040-config.h b/inc/sp140/rp2040-config.h index b220f908..f1954630 100644 --- a/inc/sp140/rp2040-config.h +++ b/inc/sp140/rp2040-config.h @@ -3,6 +3,7 @@ #define INC_SP140_RP2040_CONFIG_H_ #include "shared-config.h" +#include #define SerialESC Serial1 // ESC UART connection diff --git a/src/sp140/display.cpp b/src/sp140/display.cpp index 94c6744b..88ae110c 100644 --- a/src/sp140/display.cpp +++ b/src/sp140/display.cpp @@ -136,6 +136,7 @@ void setupDisplay(const STR_DEVICE_DATA_140_V1& deviceData, const HardwareConfig } void updateDisplay( + BatteryData& batteryData, const STR_DEVICE_DATA_140_V1& deviceData, const STR_ESC_TELEMETRY_140& escTelemetry, float altitude, bool armed, bool cruising, @@ -193,9 +194,9 @@ void updateDisplay( canvas.print(" ?%"); } - float kWatts = constrain(watts / 1000.0, 0, 50); + float kWatts = constrain(batteryData.watts / 1000.0, 0, 50); float volts = escTelemetry.volts; - float kWh = wattHoursUsed / 1000.0; + float kWh = batteryData.wattHoursUsed/ 1000.0; float amps = escTelemetry.amps; // for testing diff --git a/src/sp140/esc.cpp b/src/sp140/esc.cpp deleted file mode 100644 index 0360f434..00000000 --- a/src/sp140/esc.cpp +++ /dev/null @@ -1,208 +0,0 @@ -#include "sp140/esc.h" -#include -#include "sp140/globals.h" -#include - -Servo esc; -extern CircularBuffer voltageBuffer; - -STR_ESC_TELEMETRY_140 escTelemetryData; -static telem_esc_t raw_esc_telemdata; - -void initESC(int escPin) { - esc.attach(escPin); - esc.writeMicroseconds(ESC_DISARMED_PWM); - setupESCSerial(); -} - -void setupESCSerial() { - SerialESC.begin(ESC_BAUD_RATE); - SerialESC.setTimeout(ESC_TIMEOUT); -} - -void setESCThrottle(int throttlePWM) { - esc.writeMicroseconds(throttlePWM); -} - -void readESCTelemetry() { - prepareESCSerialRead(); - static byte escDataV2[ESC_DATA_V2_SIZE]; - SerialESC.readBytes(escDataV2, ESC_DATA_V2_SIZE); - handleESCSerialData(escDataV2); -} - -void prepareESCSerialRead() { - while (SerialESC.available() > 0) { - SerialESC.read(); - } -} - -void handleESCSerialData(byte buffer[]) { - // if(sizeof(buffer) != 22) { - // Serial.print("wrong size "); - // Serial.println(sizeof(buffer)); - // return; //Ignore malformed packets - // } - - if (buffer[20] != 255 || buffer[21] != 255) { - // Serial.println("no stop byte"); - - return; // Stop byte of 65535 not received - } - - // Check the fletcher checksum - int checkFletch = checkFletcher16(buffer); - - // checksum - raw_esc_telemdata.CSUM_HI = buffer[19]; - raw_esc_telemdata.CSUM_LO = buffer[18]; - - // TODO: alert if no new data in 3 seconds - int checkCalc = (int)(((raw_esc_telemdata.CSUM_HI << 8) + raw_esc_telemdata.CSUM_LO)); - - // Checksums do not match - if (checkFletch != checkCalc) { - return; - } - // Voltage - raw_esc_telemdata.V_HI = buffer[1]; - raw_esc_telemdata.V_LO = buffer[0]; - - float voltage = (raw_esc_telemdata.V_HI << 8 | raw_esc_telemdata.V_LO) / 100.0; - escTelemetryData.volts = voltage; // Voltage - - if (escTelemetryData.volts > BATT_MIN_V) { - escTelemetryData.volts += 1.0; // calibration - } - - voltageBuffer.push(escTelemetryData.volts); - - // Temperature - raw_esc_telemdata.T_HI = buffer[3]; - raw_esc_telemdata.T_LO = buffer[2]; - - float rawVal = (float)((raw_esc_telemdata.T_HI << 8) + raw_esc_telemdata.T_LO); - - static int SERIESRESISTOR = 10000; - static int NOMINAL_RESISTANCE = 10000; - static int NOMINAL_TEMPERATURE = 25; - static int BCOEFFICIENT = 3455; - - // convert value to resistance - float Rntc = (4096 / (float) rawVal) - 1; - Rntc = SERIESRESISTOR / Rntc; - - // Get the temperature - float temperature = Rntc / (float) NOMINAL_RESISTANCE; // (R/Ro) - temperature = (float) log(temperature); // ln(R/Ro) - temperature /= BCOEFFICIENT; // 1/B * ln(R/Ro) - - temperature += 1.0 / ((float) NOMINAL_TEMPERATURE + 273.15); // + (1/To) - temperature = 1.0 / temperature; // Invert - temperature -= 273.15; // convert to Celsius - - // filter bad values - if (temperature < 0 || temperature > 200) { - escTelemetryData.temperatureC = __FLT_MIN__; - } else { - temperature = (float) trunc(temperature * 100) / 100; // 2 decimal places - escTelemetryData.temperatureC = temperature; - } - - // Current - int16_t _amps = 0; - _amps = word(buffer[5], buffer[4]); - escTelemetryData.amps = _amps / 12.5; - - // Serial.print("amps "); - // Serial.print(currentAmpsInput); - // Serial.print(" - "); - - watts = escTelemetryData.amps * escTelemetryData.volts; - - // Reserved - raw_esc_telemdata.R0_HI = buffer[7]; - raw_esc_telemdata.R0_LO = buffer[6]; - - // eRPM - raw_esc_telemdata.RPM0 = buffer[11]; - raw_esc_telemdata.RPM1 = buffer[10]; - raw_esc_telemdata.RPM2 = buffer[9]; - raw_esc_telemdata.RPM3 = buffer[8]; - - int poleCount = 62; - uint32_t rawERPM = (raw_esc_telemdata.RPM0 << 24) | - (raw_esc_telemdata.RPM1 << 16) | - (raw_esc_telemdata.RPM2 << 8) | - raw_esc_telemdata.RPM3; - int currentERPM = static_cast(rawERPM); // ERPM output - int currentRPM = currentERPM / poleCount; // Real RPM output - escTelemetryData.eRPM = currentRPM; - - // Serial.print("RPM "); - // Serial.print(currentRPM); - // Serial.print(" - "); - - // Input Duty - raw_esc_telemdata.DUTYIN_HI = buffer[13]; - raw_esc_telemdata.DUTYIN_LO = buffer[12]; - - int throttleDuty = (int)(((raw_esc_telemdata.DUTYIN_HI << 8) + raw_esc_telemdata.DUTYIN_LO) / 10); - escTelemetryData.inPWM = (throttleDuty / 10); // Input throttle - - // Serial.print("throttle "); - // Serial.print(escTelemetryData.inPWM); - // Serial.print(" - "); - - // Motor Duty - // raw_esc_telemdata.MOTORDUTY_HI = buffer[15]; - // raw_esc_telemdata.MOTORDUTY_LO = buffer[14]; - - // int motorDuty = (int)(((raw_esc_telemdata.MOTORDUTY_HI << 8) + raw_esc_telemdata.MOTORDUTY_LO) / 10); - // int currentMotorDuty = (motorDuty / 10); // Motor duty cycle - - // Reserved - // raw_esc_telemdata.R1 = buffer[17]; - - /* Status Flags - # Bit position in byte indicates flag set, 1 is set, 0 is default - # Bit 0: Motor Started, set when motor is running as expected - # Bit 1: Motor Saturation Event, set when saturation detected and power is reduced for desync protection - # Bit 2: ESC Over temperature event occurring, shut down method as per configuration - # Bit 3: ESC Overvoltage event occurring, shut down method as per configuration - # Bit 4: ESC Undervoltage event occurring, shut down method as per configuration - # Bit 5: Startup error detected, motor stall detected upon trying to start*/ - raw_esc_telemdata.statusFlag = buffer[16]; - escTelemetryData.statusFlag = raw_esc_telemdata.statusFlag; - // Serial.print("status "); - // Serial.print(raw_esc_telemdata.statusFlag, BIN); - // Serial.print(" - "); - // Serial.println(" "); -} - -// new V2 ESC checking -int checkFletcher16(byte byteBuffer[]) { - int fCCRC16; - int i; - int c0 = 0; - int c1 = 0; - - // Calculate checksum intermediate bytesUInt16 - for (i = 0; i < 18; i++) { // Check only first 18 bytes, skip crc bytes - c0 = (int)(c0 + ((int)byteBuffer[i])) % 255; - c1 = (int)(c1 + c0) % 255; - } - // Assemble the 16-bit checksum value - fCCRC16 = (c1 << 8) | c0; - return (int)fCCRC16; -} - -// for debugging -static void printRawSentence(byte buffer[]) { - Serial.print(F("DATA: ")); - for (int i = 0; i < ESC_DATA_V2_SIZE; i++) { - Serial.print(buffer[i], HEX); - Serial.print(F(" ")); - } - Serial.println(); -} diff --git a/src/sp140/esc/FactoryEsc.cpp b/src/sp140/esc/FactoryEsc.cpp new file mode 100644 index 00000000..ed5d7a87 --- /dev/null +++ b/src/sp140/esc/FactoryEsc.cpp @@ -0,0 +1,223 @@ +#ifndef FACTORY_ESC +#define FACTORY_ESC + +#ifdef M0_PIO + #include "../../inc/sp140/m0-config.h" +#else + #include "../../inc/sp140/rp2040-config.h" +#endif + +#include +// #include +#include "../../../inc/sp140/battery/BatteryData.h" +#include "../../../inc/sp140/esc/FactoryEsc.h" +#include "../../../inc/sp140/esc/EscBase.h" +#include "sp140/structs.h" + +FactoryEsc::FactoryEsc(CircularBuffer* pVoltageBuffer) { + this->pVoltageBuffer = pVoltageBuffer; +} + +void FactoryEsc::initESC(int escPin) { + esc.attach(escPin); + esc.writeMicroseconds(ESC_DISARMED_PWM); + setupESCSerial(); +} + +void FactoryEsc::setupESCSerial() { + SerialESC.begin(ESC_BAUD_RATE); + SerialESC.setTimeout(ESC_TIMEOUT); +} + +void FactoryEsc::setESCThrottle(int throttlePWM) { + esc.writeMicroseconds(throttlePWM); +} + +void FactoryEsc::readESCTelemetry(BatteryData& batteryData, EscData& escData) { + prepareESCSerialRead(); + static byte escDataV2[ESC_DATA_V2_SIZE]; + SerialESC.readBytes(escDataV2, ESC_DATA_V2_SIZE); + handleESCSerialData(batteryData, escData, escDataV2); +} + +void FactoryEsc::prepareESCSerialRead() { + while (SerialESC.available() > 0) { + SerialESC.read(); + } +} + +void FactoryEsc::handleESCSerialData(BatteryData& batteryData, EscData& escData, byte buffer[]) { + // if(sizeof(buffer) != 22) { + // Serial.print("wrong size "); + // Serial.println(sizeof(buffer)); + // return; //Ignore malformed packets + // } + + if (buffer[20] != 255 || buffer[21] != 255) { + // Serial.println("no stop byte"); + + return; // Stop byte of 65535 not received + } + + // Check the fletcher checksum + int checkFletch = checkFletcher16(buffer); + telem_esc_t& raw_telemdata = escData.raw_esc_telemdata; + STR_ESC_TELEMETRY_140& telemeteryData = escData.escTelemetryData; + // checksum + raw_telemdata.CSUM_HI = buffer[19]; + raw_telemdata.CSUM_LO = buffer[18]; + + // TODO: alert if no new data in 3 seconds + int checkCalc = (int)(((raw_telemdata.CSUM_HI << 8) + raw_telemdata.CSUM_LO)); + + // Checksums do not match + if (checkFletch != checkCalc) { + return; + } + // Voltage + raw_telemdata.V_HI = buffer[1]; + raw_telemdata.V_LO = buffer[0]; + + float voltage = (raw_telemdata.V_HI << 8 | raw_telemdata.V_LO) / 100.0; + telemeteryData.volts = voltage; // Voltage + + if (telemeteryData.volts > BATT_MIN_V) { + telemeteryData.volts += 1.0; // calibration + } + + pVoltageBuffer->push(telemeteryData.volts); + + // Temperature + raw_telemdata.T_HI = buffer[3]; + raw_telemdata.T_LO = buffer[2]; + + float rawVal = (float)((raw_telemdata.T_HI << 8) + raw_telemdata.T_LO); + + static int SERIESRESISTOR = 10000; + static int NOMINAL_RESISTANCE = 10000; + static int NOMINAL_TEMPERATURE = 25; + static int BCOEFFICIENT = 3455; + + // convert value to resistance + float Rntc = (4096 / (float) rawVal) - 1; + Rntc = SERIESRESISTOR / Rntc; + + // Get the temperature + float temperature = Rntc / (float) NOMINAL_RESISTANCE; // (R/Ro) + temperature = (float) log(temperature); // ln(R/Ro) + temperature /= BCOEFFICIENT; // 1/B * ln(R/Ro) + + temperature += 1.0 / ((float) NOMINAL_TEMPERATURE + 273.15); // + (1/To) + temperature = 1.0 / temperature; // Invert + temperature -= 273.15; // convert to Celsius + + // filter bad values + if (temperature < 0 || temperature > 200) { + telemeteryData.temperatureC = __FLT_MIN__; + } else { + temperature = (float) trunc(temperature * 100) / 100; // 2 decimal places + telemeteryData.temperatureC = temperature; + } + + // Current + int16_t _amps = 0; + _amps = word(buffer[5], buffer[4]); + telemeteryData.amps = _amps / 12.5; + + // Serial.print("amps "); + // Serial.print(currentAmpsInput); + // Serial.print(" - "); + + batteryData.watts = telemeteryData.amps * telemeteryData.volts; + + // Reserved + raw_telemdata.R0_HI = buffer[7]; + raw_telemdata.R0_LO = buffer[6]; + + // eRPM + raw_telemdata.RPM0 = buffer[11]; + raw_telemdata.RPM1 = buffer[10]; + raw_telemdata.RPM2 = buffer[9]; + raw_telemdata.RPM3 = buffer[8]; + + int poleCount = 62; + uint32_t rawERPM = (raw_telemdata.RPM0 << 24) | + (raw_telemdata.RPM1 << 16) | + (raw_telemdata.RPM2 << 8) | + raw_telemdata.RPM3; + int currentERPM = static_cast(rawERPM); // ERPM output + int currentRPM = currentERPM / poleCount; // Real RPM output + telemeteryData.eRPM = currentRPM; + + // Serial.print("RPM "); + // Serial.print(currentRPM); + // Serial.print(" - "); + + // Input Duty + raw_telemdata.DUTYIN_HI = buffer[13]; + raw_telemdata.DUTYIN_LO = buffer[12]; + + int throttleDuty = (int)(((raw_telemdata.DUTYIN_HI << 8) + raw_telemdata.DUTYIN_LO) / 10); + telemeteryData.inPWM = (throttleDuty / 10); // Input throttle + + // Serial.print("throttle "); + // Serial.print(escTelemetryData.inPWM); + // Serial.print(" - "); + + // Motor Duty + // raw_esc_telemdata.MOTORDUTY_HI = buffer[15]; + // raw_esc_telemdata.MOTORDUTY_LO = buffer[14]; + + // int motorDuty = (int)(((raw_esc_telemdata.MOTORDUTY_HI << 8) + raw_esc_telemdata.MOTORDUTY_LO) / 10); + // int currentMotorDuty = (motorDuty / 10); // Motor duty cycle + + // Reserved + // raw_esc_telemdata.R1 = buffer[17]; + + /* Status Flags + # Bit position in byte indicates flag set, 1 is set, 0 is default + # Bit 0: Motor Started, set when motor is running as expected + # Bit 1: Motor Saturation Event, set when saturation detected and power is reduced for desync protection + # Bit 2: ESC Over temperature event occurring, shut down method as per configuration + # Bit 3: ESC Overvoltage event occurring, shut down method as per configuration + # Bit 4: ESC Undervoltage event occurring, shut down method as per configuration + # Bit 5: Startup error detected, motor stall detected upon trying to start*/ + raw_telemdata.statusFlag = buffer[16]; + telemeteryData.statusFlag = raw_telemdata.statusFlag; + // Serial.print("status "); + // Serial.print(raw_esc_telemdata.statusFlag, BIN); + // Serial.print(" - "); + // Serial.println(" "); +} + +// new V2 ESC checking +int FactoryEsc::checkFletcher16(byte byteBuffer[]) { + int fCCRC16; + int i; + int c0 = 0; + int c1 = 0; + + // Calculate checksum intermediate bytesUInt16 + for (i = 0; i < 18; i++) { // Check only first 18 bytes, skip crc bytes + c0 = (int)(c0 + ((int)byteBuffer[i])) % 255; + c1 = (int)(c1 + c0) % 255; + } + // Assemble the 16-bit checksum value + fCCRC16 = (c1 << 8) | c0; + return (int)fCCRC16; +} + +// for debugging +void FactoryEsc::printRawSentence(byte buffer[]) { + Serial.print(F("DATA: ")); + for (int i = 0; i < ESC_DATA_V2_SIZE; i++) { + Serial.print(buffer[i], HEX); + Serial.print(F(" ")); + } + Serial.println(); +} + +// FactoryEsc::~FactoryEsc() { +// } + +#endif \ No newline at end of file diff --git a/src/sp140/globals.cpp b/src/sp140/globals.cpp index fa05c369..1e463800 100644 --- a/src/sp140/globals.cpp +++ b/src/sp140/globals.cpp @@ -31,7 +31,4 @@ unsigned long cruisedAtMillis = 0; int prevPotLvl = 0; int cruisedPotVal = 0; -float watts = 0; -float wattHoursUsed = 0; - STR_DEVICE_DATA_140_V1 deviceData; diff --git a/src/sp140/sp140-helpers.ino b/src/sp140/sp140-helpers.ino index 2909360d..14bc9b24 100644 --- a/src/sp140/sp140-helpers.ino +++ b/src/sp140/sp140-helpers.ino @@ -1,5 +1,7 @@ // Copyright 2020 +#include + // initialize the buzzer void initBuzz() { pinMode(board_config.buzzer_pin, OUTPUT); @@ -39,14 +41,12 @@ int limitedThrottle(int current, int last, int threshold) { } // ring buffer for voltage readings -float getBatteryVoltSmoothed() { +float getBatteryVoltSmoothed(CircularBuffer* pVoltageBuffer) { float avg = 0.0; + if (pVoltageBuffer->isEmpty()) { return avg; } - if (voltageBuffer.isEmpty()) { return avg; } - - using index_t = decltype(voltageBuffer)::index_t; - for (index_t i = 0; i < voltageBuffer.size(); i++) { - avg += voltageBuffer[i] / voltageBuffer.size(); + for (int i = 0; i < pVoltageBuffer->size(); i++) { + avg += pVoltageBuffer->operator[](i) / pVoltageBuffer->size(); } return avg; } diff --git a/src/sp140/sp140.ino b/src/sp140/sp140.ino index ca900128..a2be7e2c 100644 --- a/src/sp140/sp140.ino +++ b/src/sp140/sp140.ino @@ -17,7 +17,7 @@ #include "../../inc/sp140/structs.h" // data structs #include // button clicks #include -#include // smooth out readings +#include #include // smoothing for throttle #include #include // convert time to hours mins etc @@ -38,13 +38,28 @@ #endif #include "../../inc/sp140/globals.h" // device config -#include "../../inc/sp140/esc.h" +#include "../../inc/sp140/battery/BatteryData.h" +#include "../../inc/sp140/esc/EscData.h" +#include "../../inc/sp140/esc/EscBase.h" +#include "../../inc/sp140/esc/FactoryEsc.h" +#include "../../inc/sp140/structs.h" #include "../../inc/sp140/display.h" #include "../../inc/sp140/altimeter.h" #include "../../inc/sp140/vibration.h" using namespace ace_button; +BatteryData batteryData; + +CircularBuffer voltageBuffer; +CircularBuffer potBuffer; + +EscData escData; +FactoryEsc factoryEsc(&voltageBuffer); +EscBase* pEsc = &factoryEsc; + + + UBaseType_t uxCoreAffinityMask0 = (1 << 0); // Core 0 UBaseType_t uxCoreAffinityMask1 = (1 << 1); // Core 1 @@ -64,9 +79,6 @@ ButtonConfig* buttonConfig; extEEPROM eep(kbits_64, 1, 64); #endif -CircularBuffer voltageBuffer; -CircularBuffer potBuffer; - Adafruit_NeoPixel pixels(1, LED_BUILTIN, NEO_GRB + NEO_KHZ800); uint32_t led_color = LED_RED; // current LED color @@ -166,7 +178,7 @@ void telemetryTask(void *pvParameters) { (void) pvParameters; // this is a standard idiom to avoid compiler warnings about unused parameters. for (;;) { // infinite loop - readESCTelemetry(); + pEsc->readESCTelemetry(batteryData, escData); delay(50); // wait for 50ms } vTaskDelete(NULL); // should never reach this @@ -189,7 +201,7 @@ void updateDisplayTask(void *pvParameters) { const float altitude = getAltitude(deviceData); bool isArmed = (currentState != DISARMED); bool isCruising = (currentState == ARMED_CRUISING); - updateDisplay(deviceData, escTelemetryData, altitude, isArmed, isCruising, armedAtMillis); + updateDisplay(batteryData, deviceData, escData.escTelemetryData, altitude, isArmed, isCruising, armedAtMillis); delay(250); } vTaskDelete(NULL); // should never reach this @@ -359,7 +371,7 @@ void psTop() { } void setup140() { - initESC(board_config.esc_pin); + pEsc->initESC(board_config.esc_pin); initBuzz(); Wire1.setSDA(A0); // Have to use Wire1 because pins are assigned that in hardware @@ -399,7 +411,7 @@ void printTime(const char* label) { } void disarmESC() { - setESCThrottle(ESC_DISARMED_PWM); + pEsc->setESCThrottle(ESC_DISARMED_PWM); } // reset smoothing @@ -570,7 +582,7 @@ void handleThrottle() { localThrottlePWM = mapd(potLvl, 0, 4095, ESC_MIN_PWM, maxPWM); } - setESCThrottle(localThrottlePWM); // using val as the signal to esc + pEsc->setESCThrottle(localThrottlePWM); // using val as the signal to esc } int averagePotBuffer() { @@ -586,7 +598,7 @@ bool armSystem() { uint16_t arm_melody[] = { 1760, 1976, 2093 }; const unsigned int arm_vibes[] = { 1, 85, 1, 85, 1, 85, 1 }; - setESCThrottle(ESC_DISARMED_PWM); // initialize the signal to low + pEsc->setESCThrottle(ESC_DISARMED_PWM); // initialize the signal to low //ledBlinkThread.enabled = false; armedAtMillis = millis(); @@ -637,6 +649,6 @@ void trackPower() { prevPwrMillis = currentPwrMillis; if (currentState != DISARMED) { - wattHoursUsed += round(watts/60/60*msec_diff)/1000.0; + batteryData.wattHoursUsed += round(batteryData.watts/60/60*msec_diff)/1000.0; } }