Most of the remaining VSS parts
This commit is contained in:
parent
1530bb892e
commit
a826b20307
|
@ -357,13 +357,13 @@ page = 1
|
|||
;vssPullup = bits, U08, 102, [1:1], "Off", "On"
|
||||
vssPin = bits, U08, 102, [2:7], "Board Default", "INVALID", "INVALID", "3", "4", "5", "6", "7", "8", "9", "10", "11", "12", "13", "14", "15", "16", "17", "18", "19", "20", "21", "22", "23", "24", "25", "26", "27", "28", "29", "30", "31", "32", "33", "34", "35", "36", "37", "38", "39", "40", "41", "42", "43", "44", "45", "46", "47", "48", "49", "50", "51", "52", "53", "54", "A8", "A9", "A10", "A11", "A12", "A13", "A14", "A15", "INVALID"
|
||||
vssPulsesPerKm= scalar, U16, 103, "pulses" 1.0, 0.0, 0.0, 25500, 0
|
||||
vssSmoothing = scalar, U08, 105, "%", 1.0, 0, 0, 255, 0
|
||||
vssRatio1 = scalar, U16, 106, "km/h per 1000rpm", 0.1, 0, 0, 99.9, 1
|
||||
vssRatio2 = scalar, U16, 108, "km/h per 1000rpm", 0.1, 0, 0, 99.9, 1
|
||||
vssRatio3 = scalar, U16, 110, "km/h per 1000rpm", 0.1, 0, 0, 99.9, 1
|
||||
vssRatio4 = scalar, U16, 112, "km/h per 1000rpm", 0.1, 0, 0, 99.9, 1
|
||||
vssRatio5 = scalar, U16, 114, "km/h per 1000rpm", 0.1, 0, 0, 99.9, 1
|
||||
vssRatio6 = scalar, U16, 116, "km/h per 1000rpm", 0.1, 0, 0, 99.9, 1
|
||||
vssSmoothing = scalar, U08, 105, "%", 1.0, 0, 0, 120, 0
|
||||
vssRatio1 = scalar, U16, 106, "km/h per 1000rpm", 0.1, 0, 0, 299.9, 1
|
||||
vssRatio2 = scalar, U16, 108, "km/h per 1000rpm", 0.1, 0, 0, 299.9, 1
|
||||
vssRatio3 = scalar, U16, 110, "km/h per 1000rpm", 0.1, 0, 0, 299.9, 1
|
||||
vssRatio4 = scalar, U16, 112, "km/h per 1000rpm", 0.1, 0, 0, 299.9, 1
|
||||
vssRatio5 = scalar, U16, 114, "km/h per 1000rpm", 0.1, 0, 0, 299.9, 1
|
||||
vssRatio6 = scalar, U16, 116, "km/h per 1000rpm", 0.1, 0, 0, 299.9, 1
|
||||
|
||||
|
||||
unused2-95 = array, U08, 118, [10], "%", 1.0, 0.0, 0.0, 255, 0
|
||||
|
@ -1036,6 +1036,9 @@ page = 11
|
|||
|
||||
;-------------------------------------------------------------------------------
|
||||
|
||||
[EventTriggers]
|
||||
triggeredPageRefresh = 1, { vssRefresh > 0 }
|
||||
|
||||
[ConstantsExtensions]
|
||||
requiresPowerCycle = nCylinders
|
||||
requiresPowerCycle = pinLayout
|
||||
|
@ -1245,7 +1248,7 @@ page = 11
|
|||
controllerPriority = vssRatio5
|
||||
controllerPriority = vssRatio6
|
||||
defaultValue = vssPulsesPerKm, 3000
|
||||
defaultValue = vssSmoothing, 128
|
||||
defaultValue = vssSmoothing, 50
|
||||
|
||||
;pinLayout = bits, U08, 15, [0:7], "Speeduino v0.1", "Speeduino v0.2", "Speeduino v0.3", "Speeduino v0.4", "INVALID", "INVALID", "01-05 MX5 PNP", "INVALID", "96-97 MX5 PNP", "NA6 MX5 PNP", "Turtana PCB", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "Plazomat I/O 0.1", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "Daz V6 Shield 0.1", "BMW PnP", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "NO2C", "UA4C", "INVALID", "INVALID", "INVALID", "DIY-EFI CORE4 v1.0", "INVALID", "INVALID", "INVALID", "INVALID", "dvjcodec Teensy RevA", "dvjcodec Teensy RevB", "INVALID", "INVALID", "INVALID", "DropBear", "INVALID", "INVALID", "INVALID", "INVALID", "Black STM32F407VET6 V0.1", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID"
|
||||
defaultValue = boardFuelOutputs, 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 6 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 8 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4 4
|
||||
|
@ -1467,6 +1470,9 @@ menuDialog = main
|
|||
fanInv = ""
|
||||
fanHyster = "The number of degrees of hysteresis to be used in controlling the fan. Recommended values are between 2 and 5"
|
||||
|
||||
vssPulsesPerKm = "The number of pulses on the VSS signal per KM/Mile"
|
||||
vssSmoothing = "A smoothing factor to help reduce noise in the VSS signal. Typical values are between 0 and 50"
|
||||
|
||||
aeTime = "The duration of the acceleration enrichment"
|
||||
aseTsnDelay = "Transition time to disable ASE"
|
||||
iacChannels = "The number of output channels used for PWM valves. Select 1 for 2-wire valves or 2 for 3-wire valves."
|
||||
|
@ -1539,7 +1545,7 @@ menuDialog = main
|
|||
|
||||
;speeduino_tsCanId = "This is the TsCanId that the Speeduino ECU will respond to. This should match the main controller CAN ID in project properties if it is connected directy to TunerStudio, Otherwise the device ID if connected via CAN passthrough"
|
||||
true_address = "This is the 11bit Can address of the Speeduino ECU "
|
||||
realtime_base_address = "This is the 11bit CAN address of the realtime data broadcast from the Speeduino ECU. This MUST be at least 0x16 greater than the true address"
|
||||
realtime_base_address = "This is the 11bit CAN address of the realtime data broadcast from the Speeduino ECU. This MUST be at least 0x16 greater than the true address"
|
||||
;obd_address = "The 11bit Can address that the Speeduino ECU responds to for OBD2 diagnostic requests"
|
||||
AUXin00Alias = "The Ascii alias asigned to Aux input channel 0"
|
||||
AUXin01Alias = "The Ascii alias asigned to Aux input channel 1"
|
||||
|
@ -1825,6 +1831,7 @@ menuDialog = main
|
|||
field = "Smoothing Factor", vssSmoothing, { vssMode > 1 }
|
||||
|
||||
dialog = vssSettings, "", yAxis
|
||||
topicHelp = "https://wiki.speeduino.com/en/configuration/VSS"
|
||||
field = "VSS Input Mode", vssMode
|
||||
field = "VSS Pin", vssPin, { vssMode > 1 }
|
||||
;field = "Use Pullup", vssPullup, { vssMode > 1 }
|
||||
|
@ -3610,7 +3617,7 @@ cmdVSSratio6 = "E\x99\x06"
|
|||
; you change it.
|
||||
|
||||
ochGetCommand = "r\$tsCanId\x30%2o%2c"
|
||||
ochBlockSize = 103
|
||||
ochBlockSize = 104
|
||||
|
||||
secl = scalar, U08, 0, "sec", 1.000, 0.000
|
||||
status1 = scalar, U08, 1, "bits", 1.000, 0.000
|
||||
|
@ -3701,7 +3708,8 @@ cmdVSSratio6 = "E\x99\x06"
|
|||
resetLockOn = bits, U08, 83, [0:0]
|
||||
nitrousOn = bits, U08, 83, [1:1]
|
||||
fuel2Active = bits, U08, 83, [2:2]
|
||||
unused81_3-4 = bits, U08, 83, [3:4]
|
||||
vssRefresh = bits, U08, 83, [3:3]
|
||||
unused81_4 = bits, U08, 83, [4:4]
|
||||
nSquirts = bits, U08, 83, [5:7]
|
||||
unused1 = scalar, U08, 84, "ADC",1.000, 0.000
|
||||
fuelLoad = scalar, S16, 85, { bitStringValue( algorithmUnits , algorithm ) }, 1.000, 0.000
|
||||
|
@ -3716,7 +3724,8 @@ cmdVSSratio6 = "E\x99\x06"
|
|||
baroCorrection = scalar, U08, 98, "%", 1.000, 0.000
|
||||
veCurr = scalar, U08, 99, "%", 1.000, 0.000
|
||||
ASECurr = scalar, U08, 100, "%", 1.000, 0.000
|
||||
vss = scalar, U16, 101, "%", 1.000, 0.000
|
||||
vss = scalar, U16, 101, "km/h", 1.000, 0.000
|
||||
gear = scalar, U08, 103, "", 1.000, 0.000
|
||||
#sd_status = scalar, U08, 99, "", 1.0, 0.0
|
||||
|
||||
#if CELSIUS
|
||||
|
@ -3844,6 +3853,8 @@ cmdVSSratio6 = "E\x99\x06"
|
|||
entry = vvtAngle, "VVT Angle", int, "%d", { vvtMode == 2 } ;;Only show when using close loop vvt
|
||||
entry = vvtTarget, "VVT Target Angle", int, "%d", { vvtMode == 2 } ;;Only show when using close loop vvt
|
||||
entry = vvtDuty, "VVT Duty", int, "%d", { vvtEnabled > 0 }
|
||||
entry = vss, "VSS (Speed)", int, "%d", { vssMode > 1 }
|
||||
entry = gear, "Gear", int, "%d", { vssMode > 1 }
|
||||
|
||||
entry = auxin_gauge0, { stringValue(AUXin00Alias)}, int, "%d", {(caninput_sel0b != 0)}
|
||||
entry = auxin_gauge1, { stringValue(AUXin01Alias)}, int, "%d", { (caninput_sel1b != 0)}
|
||||
|
|
|
@ -9,6 +9,7 @@
|
|||
#include "utils.h"
|
||||
#include "scheduledIO.h"
|
||||
#include "sensors.h"
|
||||
#include "storage.h"
|
||||
#ifdef USE_MC33810
|
||||
#include "acc_mc33810.h"
|
||||
#endif
|
||||
|
@ -320,6 +321,8 @@ uint16_t TS_CommandButtonsHandler(int buttonCommand)
|
|||
if(vssLastPulseTime > vssLastMinusOnePulseTime)
|
||||
{
|
||||
configPage2.vssPulsesPerKm = 60000000UL / (vssLastPulseTime - vssLastMinusOnePulseTime);
|
||||
writeConfig(1); // Need to manually save the new config value as it will not trigger a burn in tunerStudio due to use of ControllerPriority
|
||||
BIT_SET(currentStatus.status3, BIT_STATUS3_VSS_REFRESH); //Set the flag to trigger the UI reset
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
@ -328,42 +331,54 @@ uint16_t TS_CommandButtonsHandler(int buttonCommand)
|
|||
case TS_CMD_VSS_RATIO1:
|
||||
if(currentStatus.vss > 0)
|
||||
{
|
||||
configPage2.vssRatio1 = (currentStatus.vss * 10000) / currentStatus.RPM;
|
||||
configPage2.vssRatio1 = (currentStatus.vss * 10000UL) / currentStatus.RPM;
|
||||
writeConfig(1); // Need to manually save the new config value as it will not trigger a burn in tunerStudio due to use of ControllerPriority
|
||||
BIT_SET(currentStatus.status3, BIT_STATUS3_VSS_REFRESH); //Set the flag to trigger the UI reset
|
||||
}
|
||||
break;
|
||||
|
||||
case TS_CMD_VSS_RATIO2:
|
||||
if(currentStatus.vss > 0)
|
||||
{
|
||||
configPage2.vssRatio2 = (currentStatus.vss * 10000) / currentStatus.RPM;
|
||||
configPage2.vssRatio2 = (currentStatus.vss * 10000UL) / currentStatus.RPM;
|
||||
writeConfig(1); // Need to manually save the new config value as it will not trigger a burn in tunerStudio due to use of ControllerPriority
|
||||
BIT_SET(currentStatus.status3, BIT_STATUS3_VSS_REFRESH); //Set the flag to trigger the UI reset
|
||||
}
|
||||
break;
|
||||
|
||||
case TS_CMD_VSS_RATIO3:
|
||||
if(currentStatus.vss > 0)
|
||||
{
|
||||
configPage2.vssRatio3 = (currentStatus.vss * 10000) / currentStatus.RPM;
|
||||
configPage2.vssRatio3 = (currentStatus.vss * 10000UL) / currentStatus.RPM;
|
||||
writeConfig(1); // Need to manually save the new config value as it will not trigger a burn in tunerStudio due to use of ControllerPriority
|
||||
BIT_SET(currentStatus.status3, BIT_STATUS3_VSS_REFRESH); //Set the flag to trigger the UI reset
|
||||
}
|
||||
break;
|
||||
|
||||
case TS_CMD_VSS_RATIO4:
|
||||
if(currentStatus.vss > 0)
|
||||
{
|
||||
configPage2.vssRatio4 = (currentStatus.vss * 10000) / currentStatus.RPM;
|
||||
configPage2.vssRatio4 = (currentStatus.vss * 10000UL) / currentStatus.RPM;
|
||||
writeConfig(1); // Need to manually save the new config value as it will not trigger a burn in tunerStudio due to use of ControllerPriority
|
||||
BIT_SET(currentStatus.status3, BIT_STATUS3_VSS_REFRESH); //Set the flag to trigger the UI reset
|
||||
}
|
||||
break;
|
||||
|
||||
case TS_CMD_VSS_RATIO5:
|
||||
if(currentStatus.vss > 0)
|
||||
{
|
||||
configPage2.vssRatio5 = (currentStatus.vss * 10000) / currentStatus.RPM;
|
||||
configPage2.vssRatio5 = (currentStatus.vss * 10000UL) / currentStatus.RPM;
|
||||
writeConfig(1); // Need to manually save the new config value as it will not trigger a burn in tunerStudio due to use of ControllerPriority
|
||||
BIT_SET(currentStatus.status3, BIT_STATUS3_VSS_REFRESH); //Set the flag to trigger the UI reset
|
||||
}
|
||||
break;
|
||||
|
||||
case TS_CMD_VSS_RATIO6:
|
||||
if(currentStatus.vss > 0)
|
||||
{
|
||||
configPage2.vssRatio6 = (currentStatus.vss * 10000) / currentStatus.RPM;
|
||||
configPage2.vssRatio6 = (currentStatus.vss * 10000UL) / currentStatus.RPM;
|
||||
writeConfig(1); // Need to manually save the new config value as it will not trigger a burn in tunerStudio due to use of ControllerPriority
|
||||
BIT_SET(currentStatus.status3, BIT_STATUS3_VSS_REFRESH); //Set the flag to trigger the UI reset
|
||||
}
|
||||
break;
|
||||
|
||||
|
|
|
@ -647,7 +647,9 @@ void sendValues(uint16_t offset, uint16_t packetLength, byte cmd, byte portNum)
|
|||
fullStatus[98] = currentStatus.baroCorrection;
|
||||
fullStatus[99] = currentStatus.VE; //Current VE (%). Can be equal to VE1 or VE2 or a calculated value from both of them
|
||||
fullStatus[100] = currentStatus.ASEValue; //Current ASE (%)
|
||||
fullStatus[101] = currentStatus.vss;
|
||||
fullStatus[101] = lowByte(currentStatus.vss);
|
||||
fullStatus[102] = highByte(currentStatus.vss);
|
||||
fullStatus[103] = currentStatus.gear;
|
||||
|
||||
for(byte x=0; x<packetLength; x++)
|
||||
{
|
||||
|
@ -655,6 +657,9 @@ void sendValues(uint16_t offset, uint16_t packetLength, byte cmd, byte portNum)
|
|||
else if (portNum == 3){ CANSerial.write(fullStatus[offset+x]); }
|
||||
}
|
||||
|
||||
// Reset any flags that are being used to trigger page refreshes
|
||||
BIT_CLEAR(currentStatus.status3, BIT_STATUS3_VSS_REFRESH);
|
||||
|
||||
}
|
||||
|
||||
void sendValuesLegacy()
|
||||
|
|
|
@ -149,7 +149,7 @@
|
|||
#define BIT_STATUS3_RESET_PREVENT 0 //Indicates whether reset prevention is enabled
|
||||
#define BIT_STATUS3_NITROUS 1
|
||||
#define BIT_STATUS3_FUEL2_ACTIVE 2
|
||||
#define BIT_STATUS3_UNUSED3 3
|
||||
#define BIT_STATUS3_VSS_REFRESH 3
|
||||
#define BIT_STATUS3_UNUSED4 4
|
||||
#define BIT_STATUS3_NSQUIRTS1 5
|
||||
#define BIT_STATUS3_NSQUIRTS2 6
|
||||
|
@ -521,6 +521,7 @@ struct statuses {
|
|||
uint16_t injAngle;
|
||||
byte ASEValue;
|
||||
uint16_t vss; /**< Current speed reading. Natively stored in kph and converted to mph in TS if required */
|
||||
byte gear; /**< Current gear (Calculated from vss) */
|
||||
};
|
||||
|
||||
/**
|
||||
|
|
|
@ -1288,6 +1288,7 @@ void setPinMapping(byte boardID)
|
|||
pinFlex = 2; // Flex sensor (Must be external interrupt enabled)
|
||||
pinResetControl = 43; //Reset control output
|
||||
pinBaro = A5;
|
||||
pinVSS = 20;
|
||||
|
||||
#if defined(CORE_TEENSY35)
|
||||
pinInjector6 = 51;
|
||||
|
@ -2461,7 +2462,7 @@ void setPinMapping(byte boardID)
|
|||
}
|
||||
if(configPage2.vssMode > 1)
|
||||
{
|
||||
pinMode(pinVSS, INPUT); //Standard GM / Continental flex sensor requires pullup, but this should be onboard. The internal pullup will not work (Requires ~3.3k)!
|
||||
pinMode(pinVSS, INPUT);
|
||||
}
|
||||
if(configPage6.launchEnabled > 0)
|
||||
{
|
||||
|
|
|
@ -9,8 +9,10 @@
|
|||
#ifndef LOGGER_H
|
||||
#define LOGGER_H
|
||||
|
||||
#define LOG_ENTRY_SIZE 101 /**< The size of the live data packet. This MUST match ochBlockSize setting in the ini file */
|
||||
#define LOG_ENTRY_SIZE 104 /**< The size of the live data packet. This MUST match ochBlockSize setting in the ini file */
|
||||
#define SD_LOG_ENTRY_SIZE 104 /**< The size of the live data packet used by the SD car.*/
|
||||
|
||||
void createLog(uint8_t *array);
|
||||
void createSDLog(uint8_t *array);
|
||||
|
||||
#endif
|
|
@ -21,7 +21,7 @@
|
|||
#define KNOCK_MODE_DIGITAL 1
|
||||
#define KNOCK_MODE_ANALOG 2
|
||||
|
||||
#define VSS_GEAR_HYSTERESIS 2
|
||||
#define VSS_GEAR_HYSTERESIS 5
|
||||
|
||||
/*
|
||||
#if defined(CORE_AVR)
|
||||
|
@ -44,8 +44,8 @@ unsigned long TPSlast_time; //The time the previous TPS sample was taken
|
|||
byte MAPlast; /**< The previous MAP reading */
|
||||
unsigned long MAP_time; //The time the MAP sample was taken
|
||||
unsigned long MAPlast_time; //The time the previous MAP sample was taken
|
||||
unsigned long vssLastPulseTime; /**< The times of the last VSS_NUM_SAMPLES pulses of the VSS are stored in this array */
|
||||
unsigned long vssLastMinusOnePulseTime; /**< The times of the last VSS_NUM_SAMPLES pulses of the VSS are stored in this array */
|
||||
volatile unsigned long vssLastPulseTime; /**< The times of the last VSS_NUM_SAMPLES pulses of the VSS are stored in this array */
|
||||
volatile unsigned long vssLastMinusOnePulseTime; /**< The times of the last VSS_NUM_SAMPLES pulses of the VSS are stored in this array */
|
||||
|
||||
//These variables are used for tracking the number of running sensors values that appear to be errors. Once a threshold is reached, the sensor reading will go to default value and assume the sensor is faulty
|
||||
byte mapErrorCount = 0;
|
||||
|
@ -66,6 +66,8 @@ void readTPS(bool=true); //Allows the option to override the use of the filter
|
|||
void readO2_2();
|
||||
void flexPulse();
|
||||
void vssPulse();
|
||||
uint16_t getSpeed();
|
||||
byte getGear();
|
||||
uint16_t readAuxanalog(uint8_t analogPin);
|
||||
uint16_t readAuxdigital(uint8_t digitalPin);
|
||||
void readCLT(bool=true); //Allows the option to override the use of the filter
|
||||
|
|
|
@ -505,6 +505,7 @@ uint16_t getSpeed()
|
|||
pulseTime = vssLastPulseTime - vssLastMinusOnePulseTime;
|
||||
tempSpeed = 3600000000UL / (pulseTime * configPage2.vssPulsesPerKm); //Convert the pulse gap into km/h
|
||||
tempSpeed = ADC_FILTER(tempSpeed, configPage2.vssSmoothing, currentStatus.vss); //Apply spped smoothing factor
|
||||
if(tempSpeed > 1000) { tempSpeed = 0; } //Safety check. This usually occurs when there is a hardware issue
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -516,7 +517,7 @@ byte getGear()
|
|||
byte tempGear = 0; //Unknown gear
|
||||
if(currentStatus.vss > 0)
|
||||
{
|
||||
uint16_t pulsesPer1000rpm = (currentStatus.vss * 10000) / currentStatus.RPM; //Gives the current pulses per 1000RPM, multipled by 10 (10x is the multiplication factor for the ratios in TS)
|
||||
uint16_t pulsesPer1000rpm = (currentStatus.vss * 10000UL) / currentStatus.RPM; //Gives the current pulses per 1000RPM, multipled by 10 (10x is the multiplication factor for the ratios in TS)
|
||||
//Begin gear detection
|
||||
if( (pulsesPer1000rpm > (configPage2.vssRatio1 - VSS_GEAR_HYSTERESIS)) && (pulsesPer1000rpm < (configPage2.vssRatio1 + VSS_GEAR_HYSTERESIS)) ) { tempGear = 1; }
|
||||
else if( (pulsesPer1000rpm > (configPage2.vssRatio2 - VSS_GEAR_HYSTERESIS)) && (pulsesPer1000rpm < (configPage2.vssRatio2 + VSS_GEAR_HYSTERESIS)) ) { tempGear = 2; }
|
||||
|
|
|
@ -280,6 +280,8 @@ void loop()
|
|||
readBat();
|
||||
nitrousControl();
|
||||
idleControl(); //Perform any idle related actions. Even at higher frequencies, running 4x per second is sufficient.
|
||||
currentStatus.vss = getSpeed();
|
||||
currentStatus.gear = getGear();
|
||||
|
||||
if(eepromWritesPending == true) { writeAllConfig(); } //Check for any outstanding EEPROM writes.
|
||||
|
||||
|
|
Loading…
Reference in New Issue