Dwell error correction (#1049)

* Initial work on dwell error correction

* Fix error message in TS

* Add averaging to schedules 5-8

* Cleanup warning

* Final cleanup and comments
This commit is contained in:
Josh Stewart 2023-05-22 13:37:40 +10:00 committed by GitHub
parent 72dd807fb3
commit 1502b6ff88
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
7 changed files with 205 additions and 160 deletions

View File

@ -601,8 +601,9 @@ page = 4
vvt2CL0DutyAng = scalar, S16, 121, "deg", 1.0, 0.0, -360.0, 360.0, 0 ; * ( 2 bytes)
vvt2PWMdir = bits, U08, 123, [0:0], "Advance", "Retard"
inj4CylPairing = bits, U08, 123, [1:2], "1+3 & 2+4", "1+4 & 2+3", "INVALID", "INVALID"
unusedBits4_123 = bits, U08, 123, [3:7]
inj4CylPairing = bits, U08, 123, [1:2], "1+3 & 2+4", "1+4 & 2+3", "INVALID", "INVALID"
dwellErrCorrect = bits, U08, 123, [3:3], "Off", "On"
unusedBits4_123 = bits, U08, 123, [4:7]
ANGLEFILTER_VVT = scalar, U08, 124, "%", 1.0, 0.0, 0, 100, 0
FILTER_FLEX = scalar, U08, 125, "%", 1.0, 0.0, 0, 240, 0
@ -1683,6 +1684,7 @@ page = 15
defaultValue = useTachoSweep, 0
defaultValue = tachoSweepMaxRPM, 6000
defaultValue = perToothIgn, 0
defaultValue = dwellErrCorrect, 0
defaultValue = resetControlPin, 0
;Default ADC filter values
@ -2025,6 +2027,8 @@ menuDialog = main
sparkDur = "The duration of the spark at full dwell. Typically around 1ms"
fixAngEnable = "If enabled, timing will be locked/fixed and the ignition map will be ignored. Note that this value will be overridden by the fixed cranking value when cranking"
FixAng = "Timing will be locked at this value if the above is enabled"
perToothIgn = "This ignition mode works by adjusting in progress ignition events each time a new RPM trigger pulse is received. This can improve timing accuracy significantly where supported."
dwellErrCorrect = "A basic closed loop adjustment will be made to the dwell time to account for variations due to accel/decel. This is generally only needed on lower resolution trigger arrangements"
crankRPM = "The cranking RPM threshold. When RPM is lower than this value (and above 0) the system will be considered to be cranking"
tpsflood = "Keep throttle over this value to disable the priming pulse and cranking fuel. Used to prevent flood or clear already flooded engine"
@ -2522,10 +2526,10 @@ menuDialog = main
panel = vss_gear_detection
dialog = tacho, "Tacho"
field = "Output pin", tachoPin
field = "Tacho pulse mode", tachoMode
field = "Output speed", tachoDiv, { tachoMode == 0 }
field = "Pulse duration", tachoDuration, { tachoMode == 0 }
field = "Output pin", tachoPin
field = "Tacho pulse mode", tachoMode
field = "Output speed", tachoDiv, { tachoMode == 0 }
field = "Pulse duration", tachoDuration, { tachoMode == 0 }
field = "Tacho sweep on boot", useTachoSweep
field = "Tacho sweep Max RPM", tachoSweepMaxRPM, { useTachoSweep }
@ -2850,10 +2854,12 @@ menuDialog = main
field = "Fixed Angle", FixAng, { fixAngEnable }
field = "#Note: During cranking the fixed/locked timing angle is overridden by the Cranking advance angle value above"
dialog = newIgnitionMode, "New Ignition Mode"
field = "This option is currently will improve accuracy on most compatible triggers"
dialog = newIgnitionMode, "Per tooth ignition events"
field = "This option is will generally improve accuracy on most compatible triggers"
field = "However if timing issues are encountered, please disable this"
field = "Use new ignition mode", perToothIgn
field = "Enable per tooth timing", perToothIgn
field = "Dwell error correction", dwellErrCorrect,{ perToothIgn }
dialog = sparkSettings,"Spark Settings",4
topicHelp = "https://wiki.speeduino.com/en/configuration/Spark_Settings"
@ -2863,7 +2869,7 @@ menuDialog = main
field = "Cranking advance Angle", CrankAng
field = "Spark Outputs triggers", IgInv
panel = lockSparkSettings
panel = newIgnitionMode, {}, {TrigPattern == 0 || TrigPattern == 1 || TrigPattern == 2 || TrigPattern == 3 || TrigPattern == 4 || TrigPattern == 9 || TrigPattern == 12 || TrigPattern == 13 || TrigPattern == 16 || TrigPattern == 18 || TrigPattern == 19 || TrigPattern == 22 || TrigPattern == 24} ;Only works for missing tooth, distributor, dual wheel, GM 7X, 4g63, Miata 99-05, nissan 360, Subaru 6/7, 420a, weber-marelli, NGC Renix,
panel = newIgnitionMode, { 1 }, {TrigPattern == 0 || TrigPattern == 1 || TrigPattern == 2 || TrigPattern == 3 || TrigPattern == 4 || TrigPattern == 9 || TrigPattern == 12 || TrigPattern == 13 || TrigPattern == 16 || TrigPattern == 18 || TrigPattern == 19 || TrigPattern == 22 || TrigPattern == 24} ;Only works for missing tooth, distributor, dual wheel, GM 7X, 4g63, Miata 99-05, nissan 360, Subaru 6/7, 420a, weber-marelli, NGC Renix,
dialog = dwellSettings, "Dwell Settings", 4
topicHelp = "https://wiki.speeduino.com/en/configuration/Dwell"
@ -4932,7 +4938,8 @@ cmdVSSratio6 = "E\x99\x06"
advanceGauge = advance, "Advance (Current)", "deg", 50, -10, 0, 0, 35, 45, 0, 0
advance1Gauge = advance1, "Advance1 (Spark Table 1)", "deg",50, -10, 0, 0, 35, 45, 0, 0
advance2Gauge = advance2, "Advance2 (Spark Table 2)", "deg",50, -10, 0, 0, 35, 45, 0, 0
dwellGauge = dwell, "Ign Dwell", "mSec", 0, 35.0, 1.0, 1.2, 20, 25, 3, 3
dwellGauge = dwell, "Dwell (Requested)", "mSec", 0, 35.0, 1.0, 1.2, 20, 25, 3, 3
dwellActualGauge = dwellActual, "Dwell (Measured)", "mSec", 0, 35.0, 1.0, 1.2, 20, 25, 3, 3
boostTargetGauge = boostTarget, "Target Boost", "kPa", 0, {maphigh}, 0, 20, {mapwarn}, {mapdang}, 0, 0
boostDutyGauge = boostDuty, "Boost Duty Cycle", "%", 0, 100, -1, -1, 101, 110, 1, 1
afrTargetGauge = afrTarget, "Target AFR", "", 7, 25, {12 / 14.7 * stoich}, {13 / 14.7 * stoich}, {15 / 14.7 * stoich}, {16 / 14.7 * stoich}, 2, 2
@ -5096,107 +5103,107 @@ cmdVSSratio6 = "E\x99\x06"
;-------------------------------------------------------------------------------
[OutputChannels]
; The number of bytes MegaTune or TunerStudio should expect as a result
; of sending the "A" command to Speeduino is determined
; by the value of ochBlockSize, so be very careful when
; you change it.
; The number of bytes MegaTune or TunerStudio should expect as a result
; of sending the "A" command to Speeduino is determined
; by the value of ochBlockSize, so be very careful when
; you change it.
ochGetCommand = "r\$tsCanId\x30%2o%2c"
ochBlockSize = 125
ochGetCommand = "r\$tsCanId\x30%2o%2c"
ochBlockSize = 127
secl = scalar, U08, 0, "sec", 1.000, 0.000
status1 = scalar, U08, 1, "bits", 1.000, 0.000
inj1Status = bits, U08, 1, [0:0]
inj2Status = bits, U08, 1, [1:1]
inj3Status = bits, U08, 1, [2:2]
inj4Status = bits, U08, 1, [3:3]
DFCOOn = bits, U08, 1, [4:4]
boostCutFuel = bits, U08, 1, [5:5]
toothLog1Ready = bits, U08, 1, [6:6]
toothLog2Ready = bits, U08, 1, [7:7]
engine = scalar, U08, 2, "bits", 1.000, 0.000
running = bits, U08, 2, [0:0]
crank = bits, U08, 2, [1:1]
ase = bits, U08, 2, [2:2]
warmup = bits, U08, 2, [3:3]
tpsaccaen = bits, U08, 2, [4:4]
tpsaccden = bits, U08, 2, [5:5]
mapaccaen = bits, U08, 2, [6:6]
mapaccden = bits, U08, 2, [7:7]
syncLossCounter = scalar, U08, 3, "", 1.000, 0.000
map = scalar, U16, 4, "kpa", 1.000, 0.000
iatRaw = scalar, U08, 6, "°C", 1.000, 0.000
coolantRaw = scalar, U08, 7, "°C", 1.000, 0.000
batCorrection = scalar, U08, 8, "%", 1.000, 0.000
batteryVoltage = scalar, U08, 9, "V", 0.100, 0.000
afr = scalar, U08, 10, "O2", 0.100, 0.000
egoCorrection = scalar, U08, 11, "%", 1.000, 0.000
airCorrection = scalar, U08, 12, "%", 1.000, 0.000
warmupEnrich = scalar, U08, 13, "%", 1.000, 0.000
rpm = scalar, U16, 14, "rpm", 1.000, 0.000
accelEnrich = scalar, U08, 16, "%", 2.000, 0.000
gammaEnrich = scalar, U16, 17, "%", 1.000, 0.000
VE1 = scalar, U08, 19, "%", 1.000, 0.000
VE2 = scalar, U08, 20, "%", 1.000, 0.000
afrTarget = scalar, U08, 21, "O2", 0.100, 0.000
TPSdot = scalar, S16, 22, "%/s", 1.000, 0.000
advance = scalar, S08, 24, "deg", 1.000, 0.000
tps = scalar, U08, 25, "%", 0.500, 0.000
loopsPerSecond = scalar, U16, 26, "loops", 1.000, 0.000
freeRAM = scalar, U16, 28, "bytes", 1.000, 0.000
boostTarget = scalar, U08, 30, "kPa", 2.000, 0.000
boostDuty = scalar, U08, 31, "%", 1.000, 0.000
status2 = scalar, U08, 32, "bits", 1.000, 0.000
launchHard = bits, U08, 32, [0:0]
launchSoft = bits, U08, 32, [1:1]
hardLimitOn = bits, U08, 32, [2:2]
softlimitOn = bits, U08, 32, [3:3]
boostCutSpark = bits, U08, 32, [4:4]
error = bits, U08, 32, [5:5]
idleControlOn = bits, U08, 32, [6:6]
sync = bits, U08, 32, [7:7]
rpmDOT = scalar, S16, 33, "rpm/s", 1.000, 0.000
flex = scalar, U08, 35, "%", 1.000, 0.000
flexFuelCor = scalar, U08, 36, "%", 1.000, 0.000
flexIgnCor = scalar, S08, 37, "deg", 1.000, 0.000
idleLoad = scalar, U08, 38, { bitStringValue( idleUnits , iacAlgorithm ) }, { (iacAlgorithm == 2 || iacAlgorithm == 3 || iacAlgorithm == 6 || iacMaxSteps <= 255) ? 1.000 : 2.000 }, 0.000 ; This is a combined variable covering both PWM and stepper IACs. The units and precision used depend on which idle algorithm is chosen
testoutputs = scalar, U08, 39, "bits", 1.000, 0.000
testenabled = bits, U08, 39, [0:0]
testactive = bits, U08, 39, [1:1]
afr2 = scalar, U08, 40, "O2", 0.100, 0.000
baro = scalar, U08, 41, "kpa", 1.000, 0.000
auxin_gauge0 = scalar, U16, 42, "", 1.000, 0.000
auxin_gauge1 = scalar, U16, 44, "", 1.000, 0.000
auxin_gauge2 = scalar, U16, 46, "", 1.000, 0.000
auxin_gauge3 = scalar, U16, 48, "", 1.000, 0.000
auxin_gauge4 = scalar, U16, 50, "", 1.000, 0.000
auxin_gauge5 = scalar, U16, 52, "", 1.000, 0.000
auxin_gauge6 = scalar, U16, 54, "", 1.000, 0.000
auxin_gauge7 = scalar, U16, 56, "", 1.000, 0.000
auxin_gauge8 = scalar, U16, 58, "", 1.000, 0.000
auxin_gauge9 = scalar, U16, 60, "", 1.000, 0.000
auxin_gauge10 = scalar, U16, 62, "", 1.000, 0.000
auxin_gauge11 = scalar, U16, 64, "", 1.000, 0.000
auxin_gauge12 = scalar, U16, 66, "", 1.000, 0.000
auxin_gauge13 = scalar, U16, 68, "", 1.000, 0.000
auxin_gauge14 = scalar, U16, 70, "", 1.000, 0.000
auxin_gauge15 = scalar, U16, 72, "", 1.000, 0.000
tpsADC = scalar, U08, 74, "ADC", 1.000, 0.000
errors = scalar, U08, 75, "bits", 1.000, 0.000
secl = scalar, U08, 0, "sec", 1.000, 0.000
status1 = scalar, U08, 1, "bits", 1.000, 0.000
inj1Status = bits, U08, 1, [0:0]
inj2Status = bits, U08, 1, [1:1]
inj3Status = bits, U08, 1, [2:2]
inj4Status = bits, U08, 1, [3:3]
DFCOOn = bits, U08, 1, [4:4]
boostCutFuel = bits, U08, 1, [5:5]
toothLog1Ready = bits, U08, 1, [6:6]
toothLog2Ready = bits, U08, 1, [7:7]
engine = scalar, U08, 2, "bits", 1.000, 0.000
running = bits, U08, 2, [0:0]
crank = bits, U08, 2, [1:1]
ase = bits, U08, 2, [2:2]
warmup = bits, U08, 2, [3:3]
tpsaccaen = bits, U08, 2, [4:4]
tpsaccden = bits, U08, 2, [5:5]
mapaccaen = bits, U08, 2, [6:6]
mapaccden = bits, U08, 2, [7:7]
syncLossCounter = scalar, U08, 3, "", 1.000, 0.000
map = scalar, U16, 4, "kpa", 1.000, 0.000
iatRaw = scalar, U08, 6, "°C", 1.000, 0.000
coolantRaw = scalar, U08, 7, "°C", 1.000, 0.000
batCorrection = scalar, U08, 8, "%", 1.000, 0.000
batteryVoltage = scalar, U08, 9, "V", 0.100, 0.000
afr = scalar, U08, 10, "O2", 0.100, 0.000
egoCorrection = scalar, U08, 11, "%", 1.000, 0.000
airCorrection = scalar, U08, 12, "%", 1.000, 0.000
warmupEnrich = scalar, U08, 13, "%", 1.000, 0.000
rpm = scalar, U16, 14, "rpm", 1.000, 0.000
accelEnrich = scalar, U08, 16, "%", 2.000, 0.000
gammaEnrich = scalar, U16, 17, "%", 1.000, 0.000
VE1 = scalar, U08, 19, "%", 1.000, 0.000
VE2 = scalar, U08, 20, "%", 1.000, 0.000
afrTarget = scalar, U08, 21, "O2", 0.100, 0.000
TPSdot = scalar, S16, 22, "%/s", 1.000, 0.000
advance = scalar, S08, 24, "deg", 1.000, 0.000
tps = scalar, U08, 25, "%", 0.500, 0.000
loopsPerSecond = scalar, U16, 26, "loops", 1.000, 0.000
freeRAM = scalar, U16, 28, "bytes", 1.000, 0.000
boostTarget = scalar, U08, 30, "kPa", 2.000, 0.000
boostDuty = scalar, U08, 31, "%", 1.000, 0.000
status2 = scalar, U08, 32, "bits", 1.000, 0.000
launchHard = bits, U08, 32, [0:0]
launchSoft = bits, U08, 32, [1:1]
hardLimitOn = bits, U08, 32, [2:2]
softlimitOn = bits, U08, 32, [3:3]
boostCutSpark = bits, U08, 32, [4:4]
error = bits, U08, 32, [5:5]
idleControlOn = bits, U08, 32, [6:6]
sync = bits, U08, 32, [7:7]
rpmDOT = scalar, S16, 33, "rpm/s", 1.000, 0.000
flex = scalar, U08, 35, "%", 1.000, 0.000
flexFuelCor = scalar, U08, 36, "%", 1.000, 0.000
flexIgnCor = scalar, S08, 37, "deg", 1.000, 0.000
idleLoad = scalar, U08, 38, { bitStringValue( idleUnits , iacAlgorithm ) }, { (iacAlgorithm == 2 || iacAlgorithm == 3 || iacAlgorithm == 6 || iacMaxSteps <= 255) ? 1.000 : 2.000 }, 0.000 ; This is a combined variable covering both PWM and stepper IACs. The units and precision used depend on which idle algorithm is chosen
testoutputs = scalar, U08, 39, "bits", 1.000, 0.000
testenabled = bits, U08, 39, [0:0]
testactive = bits, U08, 39, [1:1]
afr2 = scalar, U08, 40, "O2", 0.100, 0.000
baro = scalar, U08, 41, "kpa", 1.000, 0.000
auxin_gauge0 = scalar, U16, 42, "", 1.000, 0.000
auxin_gauge1 = scalar, U16, 44, "", 1.000, 0.000
auxin_gauge2 = scalar, U16, 46, "", 1.000, 0.000
auxin_gauge3 = scalar, U16, 48, "", 1.000, 0.000
auxin_gauge4 = scalar, U16, 50, "", 1.000, 0.000
auxin_gauge5 = scalar, U16, 52, "", 1.000, 0.000
auxin_gauge6 = scalar, U16, 54, "", 1.000, 0.000
auxin_gauge7 = scalar, U16, 56, "", 1.000, 0.000
auxin_gauge8 = scalar, U16, 58, "", 1.000, 0.000
auxin_gauge9 = scalar, U16, 60, "", 1.000, 0.000
auxin_gauge10 = scalar, U16, 62, "", 1.000, 0.000
auxin_gauge11 = scalar, U16, 64, "", 1.000, 0.000
auxin_gauge12 = scalar, U16, 66, "", 1.000, 0.000
auxin_gauge13 = scalar, U16, 68, "", 1.000, 0.000
auxin_gauge14 = scalar, U16, 70, "", 1.000, 0.000
auxin_gauge15 = scalar, U16, 72, "", 1.000, 0.000
tpsADC = scalar, U08, 74, "ADC", 1.000, 0.000
errors = scalar, U08, 75, "bits", 1.000, 0.000
errorNum = bits, U08, 75, [0:1]
currentError = bits, U08, 75, [2:7]
pulseWidth = scalar, U16, 76, "ms", 0.001, 0.000
pulseWidth2 = scalar, U16, 78, "ms", 0.001, 0.000
pulseWidth3 = scalar, U16, 80, "ms", 0.001, 0.000
pulseWidth4 = scalar, U16, 82, "ms", 0.001, 0.000
status3 = scalar, U08, 84, "bits", 1.000, 0.000
pulseWidth = scalar, U16, 76, "ms", 0.001, 0.000
pulseWidth2 = scalar, U16, 78, "ms", 0.001, 0.000
pulseWidth3 = scalar, U16, 80, "ms", 0.001, 0.000
pulseWidth4 = scalar, U16, 82, "ms", 0.001, 0.000
status3 = scalar, U08, 84, "bits", 1.000, 0.000
resetLockOn = bits, U08, 84, [0:0]
nitrousOn = bits, U08, 84, [1:1]
fuel2Active = bits, U08, 84, [2:2]
vssRefresh = bits, U08, 84, [3:3]
halfSync = bits, U08, 84, [4:4]
nSquirts = bits, U08, 84, [5:7]
engineProtectStatus = scalar, U08, 85, "bits", 1.000, 0.000
engineProtectStatus = scalar, U08, 85, "bits", 1.000, 0.000
engineProtectRPM = bits, U08, 85, [0:0]
engineProtectMAP = bits, U08, 85, [1:1]
engineProtectOil = bits, U08, 85, [2:2]
@ -5204,58 +5211,59 @@ cmdVSSratio6 = "E\x99\x06"
engineProtectCoolant = bits, U08, 85, [4:4]
engineProtectOth = bits, U08, 85, [5:6] ; Unused for now
IOError = bits, U08, 85, [7:7]
fuelLoad = scalar, S16, 86, { bitStringValue( algorithmUnits , algorithm ) }, fuelLoadFeedBack, 0.000
ignLoad = scalar, S16, 88, { bitStringValue( algorithmUnits , ignAlgorithm ) }, ignLoadFeedBack, 0.000
dwell = scalar, U16, 90, "ms", 0.001, 0.000
CLIdleTarget = scalar, U08, 92, "RPM", 10.00, 0.000
MAPdot = scalar, S16, 93, "kPa/s", 1.000, 0.000
vvt1Angle = scalar, S16, 95, "deg", 0.50, 0.000
vvt1Target = scalar, U08, 97, "deg", 0.50, 0.000
vvt1Duty = scalar, U08, 98, "%", 0.50, 0.000
flexBoostCor = scalar, S16, 99, "kPa", 1.000, 0.000
baroCorrection = scalar, U08, 101, "%", 1.000, 0.000
veCurr = scalar, U08, 102, "%", 1.000, 0.000
ASECurr = scalar, U08, 103, "%", 1.000, 0.000
vss = scalar, U16, 104, "km/h", 1.000, 0.000
gear = scalar, U08, 106, "", 1.000, 0.000
fuelPressure = scalar, U08, 107, "PSI", 1.000, 0.000
oilPressure = scalar, U08, 108, "PSI", 1.000, 0.000
wmiPW = scalar, U08, 109, "%", 1.000, 0.000
status4 = scalar, U08, 110, "bits", 1.000, 0.000
wmiEmptyBit = bits, U08, 110, [0:0]
vvt1Error = bits, U08, 110, [1:1]
vvt2Error = bits, U08, 110, [2:2]
fanStatus = bits, U08, 110, [3:3]
burnPending = bits, U08, 110, [4:4]
stagingActive = bits, U08, 110, [5:5]
UnusedBits4 = bits, U08, 110, [6:7]
vvt2Angle = scalar, S16, 111, "deg", 0.50, 0.000
vvt2Target = scalar, U08, 113, "deg", 0.50, 0.000
vvt2Duty = scalar, U08, 114, "%", 0.50, 0.000
outputsStatus0 = bits, U08, 115, [0:0]
outputsStatus1 = bits, U08, 115, [1:1]
outputsStatus2 = bits, U08, 115, [2:2]
outputsStatus3 = bits, U08, 115, [3:3]
outputsStatus4 = bits, U08, 115, [4:4]
outputsStatus5 = bits, U08, 115, [5:5]
outputsStatus6 = bits, U08, 115, [6:6]
outputsStatus7 = bits, U08, 115, [7:7]
fuelTempRaw = scalar, U08, 116, "°C", 1.000, 0.000
fuelTempCor = scalar, U08, 117, "%", 1.000, 0.000
advance1 = scalar, S08, 118, "deg", 1.000, 0.000
advance2 = scalar, S08, 119, "deg", 1.000, 0.000
sd_status = scalar, U08, 120, "", 1.0, 0.0
emap = scalar, U16, 121, "kpa", 1.000, 0.000
fanDuty = scalar, U08, 123, "%", 0.5, 0.000
airConStatus = scalar, U08, 124, "bits", 1.000, 0.000
airConRequest = bits, U08, 124, [0:0]
airConCompressor = bits, U08, 124, [1:1]
fuelLoad = scalar, S16, 86, { bitStringValue( algorithmUnits , algorithm ) }, fuelLoadFeedBack, 0.000
ignLoad = scalar, S16, 88, { bitStringValue( algorithmUnits , ignAlgorithm ) }, ignLoadFeedBack, 0.000
dwell = scalar, U16, 90, "ms", 0.001, 0.000
CLIdleTarget = scalar, U08, 92, "RPM", 10.00, 0.000
MAPdot = scalar, S16, 93, "kPa/s", 1.000, 0.000
vvt1Angle = scalar, S16, 95, "deg", 0.50, 0.000
vvt1Target = scalar, U08, 97, "deg", 0.50, 0.000
vvt1Duty = scalar, U08, 98, "%", 0.50, 0.000
flexBoostCor = scalar, S16, 99, "kPa", 1.000, 0.000
baroCorrection = scalar, U08, 101, "%", 1.000, 0.000
veCurr = scalar, U08, 102, "%", 1.000, 0.000
ASECurr = scalar, U08, 103, "%", 1.000, 0.000
vss = scalar, U16, 104, "km/h", 1.000, 0.000
gear = scalar, U08, 106, "", 1.000, 0.000
fuelPressure = scalar, U08, 107, "PSI", 1.000, 0.000
oilPressure = scalar, U08, 108, "PSI", 1.000, 0.000
wmiPW = scalar, U08, 109, "%", 1.000, 0.000
status4 = scalar, U08, 110, "bits", 1.000, 0.000
wmiEmptyBit = bits, U08, 110, [0:0]
vvt1Error = bits, U08, 110, [1:1]
vvt2Error = bits, U08, 110, [2:2]
fanStatus = bits, U08, 110, [3:3]
burnPending = bits, U08, 110, [4:4]
stagingActive = bits, U08, 110, [5:5]
UnusedBits4 = bits, U08, 110, [6:7]
vvt2Angle = scalar, S16, 111, "deg", 0.50, 0.000
vvt2Target = scalar, U08, 113, "deg", 0.50, 0.000
vvt2Duty = scalar, U08, 114, "%", 0.50, 0.000
outputsStatus0 = bits, U08, 115, [0:0]
outputsStatus1 = bits, U08, 115, [1:1]
outputsStatus2 = bits, U08, 115, [2:2]
outputsStatus3 = bits, U08, 115, [3:3]
outputsStatus4 = bits, U08, 115, [4:4]
outputsStatus5 = bits, U08, 115, [5:5]
outputsStatus6 = bits, U08, 115, [6:6]
outputsStatus7 = bits, U08, 115, [7:7]
fuelTempRaw = scalar, U08, 116, "°C", 1.000, 0.000
fuelTempCor = scalar, U08, 117, "%", 1.000, 0.000
advance1 = scalar, S08, 118, "deg", 1.000, 0.000
advance2 = scalar, S08, 119, "deg", 1.000, 0.000
sd_status = scalar, U08, 120, "", 1.0, 0.0
emap = scalar, U16, 121, "kpa", 1.000, 0.000
fanDuty = scalar, U08, 123, "%", 0.5, 0.000
airConStatus = scalar, U08, 124, "bits", 1.000, 0.000
airConRequest = bits, U08, 124, [0:0]
airConCompressor = bits, U08, 124, [1:1]
airConRPMMLockout = bits, U08, 124, [2:2]
airConTPSLockout = bits, U08, 124, [3:3]
airConTurningOn = bits, U08, 124, [4:4]
airConCLTLockout = bits, U08, 124, [5:5]
airConFanStatus = bits, U08, 124, [6:6]
airConUnusedBits = bits, U08, 124, [7:7]
airConTPSLockout = bits, U08, 124, [3:3]
airConTurningOn = bits, U08, 124, [4:4]
airConCLTLockout = bits, U08, 124, [5:5]
airConFanStatus = bits, U08, 124, [6:6]
airConUnusedBits = bits, U08, 124, [7:7]
dwellActual = scalar, U16, 125, "ms", 0.001, 0.000
;sd_filenum = scalar, U16, 125, "", 1, 0
;sd_error = scalar, U08, 127, "", 1, 0
;sd_phase = scalar, U08, 128, "", 1, 0
@ -5400,7 +5408,8 @@ cmdVSSratio6 = "E\x99\x06"
entry = dutyCycle, "DutyCycle1", float, "%.1f"
entry = TPSdot, "TPS DOT", int, "%d", { aeMode == 0 }
entry = advance, "Advance (Current)",int, "%d"
entry = dwell, "Dwell", float, "%.1f"
entry = dwell, "Dwell", float, "%.3f"
entry = dwellActual, "Dwell (Measured)", float, "%.3f", { perToothIgn }
entry = batteryVoltage, "Battery V", float, "%.1f"
entry = rpmDOT, "rpm/s", int, "%d"
entry = flex, "Eth %", int, "%d", { flexEnabled }

View File

@ -942,26 +942,45 @@ uint16_t correctionsDwell(uint16_t dwell)
{
uint16_t tempDwell = dwell;
uint16_t sparkDur_uS = (configPage4.sparkDur * 100); //Spark duration is in mS*10. Multiple it by 100 to get spark duration in uS
if(currentStatus.actualDwell == 0) { currentStatus.actualDwell = tempDwell; } //Initialise the actualDwell value if this is the first time being called
//**************************************************************************************************************************
//Pull battery voltage based dwell correction and apply if needed
currentStatus.dwellCorrection = table2D_getValue(&dwellVCorrectionTable, currentStatus.battery10);
if (currentStatus.dwellCorrection != 100) { tempDwell = div100(dwell) * currentStatus.dwellCorrection; }
//Dwell limiter
//**************************************************************************************************************************
//Dwell error correction is a basic closed loop to keep the dwell time consistent even when adjusting its end time for the per tooth timing.
//This is mostly of benefit to low resolution triggers at low rpm (<1500)
if( (configPage2.perToothIgn == true) && (configPage4.dwellErrCorrect == 1) )
{
int16_t error = tempDwell - currentStatus.actualDwell;
if(tempDwell > INT16_MAX) { tempDwell = INT16_MAX; } //Prevent overflow when casting to signed int
if(error > ((int16_t)tempDwell / 2)) { error += error; } //Double correction amount if actual dwell is less than 50% of the requested dwell
if(error > 0) { tempDwell += error; }
}
//**************************************************************************************************************************
/*
Dwell limiter - If the total required dwell time per revolution is longer than the maximum time available at the current RPM, reduce dwell. This can occur if there are multiple sparks per revolution
This only times this can occur are:
1. Single channel spark mode where there will be nCylinders/2 sparks per revolution
2. Rotary ignition in wasted spark configuration (FC/FD), results in 2 pulses per rev. RX-8 is fully sequential resulting in 1 pulse, so not required
*/
uint16_t dwellPerRevolution = tempDwell + sparkDur_uS;
int8_t pulsesPerRevolution = 1;
//Single channel spark mode is the only time there will be more than 1 pulse per revolution on any given output
//For rotary ignition this also holds true in wasted spark configuration (FC/FD) resulting in 2 pulses. RX-8 however is fully sequential resulting in 1 pulse
if( ( (configPage4.sparkMode == IGN_MODE_SINGLE) || ((configPage4.sparkMode == IGN_MODE_ROTARY) && (configPage10.rotaryType != ROTARY_IGN_RX8)) ) && (configPage2.nCylinders > 1) ) //No point in running this for 1 cylinder engines
{
pulsesPerRevolution = (configPage2.nCylinders >> 1);
dwellPerRevolution = dwellPerRevolution * pulsesPerRevolution;
}
if(dwellPerRevolution > revolutionTime)
{
//Possibly need some method of reducing spark duration here as well, but this is a start
uint16_t adjustedSparkDur = (sparkDur_uS * revolutionTime) / dwellPerRevolution;
tempDwell = (revolutionTime / pulsesPerRevolution) - adjustedSparkDur;
}
return tempDwell;
}

View File

@ -1082,7 +1082,7 @@ void triggerSec_BasicDistributor(void) { return; } //Not required
uint16_t getRPM_BasicDistributor(void)
{
uint16_t tempRPM;
if( currentStatus.RPM < currentStatus.crankRPM)
if( currentStatus.RPM < currentStatus.crankRPM || currentStatus.RPM < 1500)
{
tempRPM = crankingGetRPM(triggerActualTeeth, 720);
}

View File

@ -661,6 +661,7 @@ struct statuses {
int O2ADC;
int O2_2ADC;
int dwell; ///< dwell (coil primary winding/circuit on) time (in ms * 10 ? See @ref correctionsDwell)
volatile int16_t actualDwell; ///< actual dwell time if new ignition mode is used (in uS)
byte dwellCorrection; /**< The amount of correction being applied to the dwell time (in unit ...). */
byte battery10; /**< The current BRV in volts (multiplied by 10. Eg 12.5V = 125) */
int8_t advance; /**< The current advance value being used in the spark calculation. Can be the same as advance1 or advance2, or a calculated value of both */
@ -1010,7 +1011,8 @@ struct config4 {
int16_t vvt2CL0DutyAng;
byte vvt2PWMdir : 1;
byte inj4cylPairing : 2;
byte unusedBits4 : 5;
byte dwellErrCorrect : 1;
byte unusedBits4 : 4;
byte ANGLEFILTER_VVT;
byte FILTER_FLEX;
byte vvtMinClt;

View File

@ -169,6 +169,8 @@ byte getTSLogEntry(uint16_t byteNum)
case 122: statusValue = highByte(currentStatus.EMAP); break;
case 123: statusValue = currentStatus.fanDuty; break;
case 124: statusValue = currentStatus.airConStatus; break;
case 125: statusValue = lowByte(currentStatus.actualDwell); break;
case 126: statusValue = highByte(currentStatus.actualDwell); break;
}
return statusValue;
@ -291,6 +293,7 @@ int16_t getReadableLogEntry(uint16_t logIndex)
case 87: statusValue = currentStatus.EMAP; break;
case 88: statusValue = currentStatus.fanDuty; break;
case 89: statusValue = currentStatus.airConStatus; break;
case 90: statusValue = currentStatus.actualDwell; break;
}
return statusValue;

View File

@ -46,6 +46,10 @@ See page 136 of the processors datasheet: http://www.atmel.com/Images/doc2549.pd
#define USE_IGN_REFRESH
#define IGNITION_REFRESH_THRESHOLD 30 //Time in uS that the refresh functions will check to ensure there is enough time before changing the end compare
#define DWELL_AVERAGE_ALPHA 30
#define DWELL_AVERAGE(input) (((long)input * (256 - DWELL_AVERAGE_ALPHA) + ((long)currentStatus.actualDwell * DWELL_AVERAGE_ALPHA))) >> 8
//#define DWELL_AVERAGE(input) (currentStatus.dwell) //Can be use to disable the above for testing
extern void (*inj1StartFunction)(void);
extern void (*inj1EndFunction)(void);
extern void (*inj2StartFunction)(void);

View File

@ -1199,6 +1199,7 @@ inline void ignitionSchedule1Interrupt(void)
ignitionSchedule1.schedulesSet = 0;
ignitionSchedule1.endScheduleSetByDecoder = false;
ignitionCount += 1; //Increment the ignition counter
currentStatus.actualDwell = DWELL_AVERAGE( (micros() - ignitionSchedule1.startTime) );
//If there is a next schedule queued up, activate it
if(ignitionSchedule1.hasNextSchedule == true)
@ -1240,6 +1241,7 @@ inline void ignitionSchedule2Interrupt(void)
ignitionSchedule2.schedulesSet = 0;
ignitionSchedule2.endScheduleSetByDecoder = false;
ignitionCount += 1; //Increment the ignition counter
currentStatus.actualDwell = DWELL_AVERAGE( (micros() - ignitionSchedule2.startTime) );
//If there is a next schedule queued up, activate it
if(ignitionSchedule2.hasNextSchedule == true)
@ -1281,6 +1283,7 @@ inline void ignitionSchedule3Interrupt(void)
ignitionSchedule3.schedulesSet = 0;
ignitionSchedule3.endScheduleSetByDecoder = false;
ignitionCount += 1; //Increment the ignition counter
currentStatus.actualDwell = DWELL_AVERAGE( (micros() - ignitionSchedule3.startTime) );
//If there is a next schedule queued up, activate it
if(ignitionSchedule3.hasNextSchedule == true)
@ -1322,6 +1325,7 @@ inline void ignitionSchedule4Interrupt(void)
ignitionSchedule4.schedulesSet = 0;
ignitionSchedule4.endScheduleSetByDecoder = false;
ignitionCount += 1; //Increment the ignition counter
currentStatus.actualDwell = DWELL_AVERAGE( (micros() - ignitionSchedule4.startTime) );
//If there is a next schedule queued up, activate it
if(ignitionSchedule4.hasNextSchedule == true)
@ -1363,6 +1367,7 @@ inline void ignitionSchedule5Interrupt(void)
ignitionSchedule5.schedulesSet = 0;
ignitionSchedule5.endScheduleSetByDecoder = false;
ignitionCount += 1; //Increment the ignition counter
currentStatus.actualDwell = DWELL_AVERAGE( (micros() - ignitionSchedule5.startTime) );
//If there is a next schedule queued up, activate it
if(ignitionSchedule5.hasNextSchedule == true)
@ -1404,6 +1409,7 @@ inline void ignitionSchedule6Interrupt(void)
ignitionSchedule6.schedulesSet = 0;
ignitionSchedule6.endScheduleSetByDecoder = false;
ignitionCount += 1; //Increment the ignition counter
currentStatus.actualDwell = DWELL_AVERAGE( (micros() - ignitionSchedule6.startTime) );
//If there is a next schedule queued up, activate it
if(ignitionSchedule6.hasNextSchedule == true)
@ -1445,6 +1451,7 @@ inline void ignitionSchedule7Interrupt(void)
ignitionSchedule7.schedulesSet = 0;
ignitionSchedule7.endScheduleSetByDecoder = false;
ignitionCount += 1; //Increment the ignition counter
currentStatus.actualDwell = DWELL_AVERAGE( (micros() - ignitionSchedule7.startTime) );
//If there is a next schedule queued up, activate it
if(ignitionSchedule7.hasNextSchedule == true)
@ -1486,6 +1493,7 @@ inline void ignitionSchedule8Interrupt(void)
ignitionSchedule8.schedulesSet = 0;
ignitionSchedule8.endScheduleSetByDecoder = false;
ignitionCount += 1; //Increment the ignition counter
currentStatus.actualDwell = DWELL_AVERAGE( (micros() - ignitionSchedule8.startTime) );
//If there is a next schedule queued up, activate it
if(ignitionSchedule8.hasNextSchedule == true)