This commit is contained in:
Josh Stewart 2020-07-27 10:12:03 +10:00
commit 2dd28278a2
17 changed files with 343 additions and 141 deletions

View File

@ -830,7 +830,7 @@
<constant digits="0" name="egoCount">16.0</constant> <constant digits="0" name="egoCount">16.0</constant>
<constant name="vvtMode">"On/Off"</constant> <constant name="vvtMode">"On/Off"</constant>
<constant name="vvtLoadSource">"MAP"</constant> <constant name="vvtLoadSource">"MAP"</constant>
<constant name="vvtCLDir">"Advance"</constant> <constant name="vvtPWMdir">"Advance"</constant>
<constant name="vvtCLUseHold">"No"</constant> <constant name="vvtCLUseHold">"No"</constant>
<constant name="vvtCLAlterFuelTiming">"No"</constant> <constant name="vvtCLAlterFuelTiming">"No"</constant>
<constant name="unused6-6">"MAP"</constant> <constant name="unused6-6">"MAP"</constant>
@ -840,7 +840,7 @@
<constant digits="0" name="ego_sdelay" units="sec">15.0</constant> <constant digits="0" name="ego_sdelay" units="sec">15.0</constant>
<constant digits="0" name="egoRPM" units="rpm">1200.0</constant> <constant digits="0" name="egoRPM" units="rpm">1200.0</constant>
<constant digits="0" name="egoTPSMax" units="%">70.0</constant> <constant digits="0" name="egoTPSMax" units="%">70.0</constant>
<constant name="vvtPin">"26"</constant> <constant name="vvt1Pin">"26"</constant>
<constant name="useExtBaro">"No"</constant> <constant name="useExtBaro">"No"</constant>
<constant name="boostMode">"Simple"</constant> <constant name="boostMode">"Simple"</constant>
<constant name="boostPin">"20"</constant> <constant name="boostPin">"20"</constant>

View File

@ -700,7 +700,7 @@
<constant digits="0" name="egoCount">16.0</constant> <constant digits="0" name="egoCount">16.0</constant>
<constant name="vvtMode">"On/Off"</constant> <constant name="vvtMode">"On/Off"</constant>
<constant name="vvtLoadSource">"MAP"</constant> <constant name="vvtLoadSource">"MAP"</constant>
<constant name="vvtCLDir">"Advance"</constant> <constant name="vvtPWMdir">"Advance"</constant>
<constant name="vvtCLUseHold">"Yes"</constant> <constant name="vvtCLUseHold">"Yes"</constant>
<constant name="vvtCLAlterFuelTiming">"No"</constant> <constant name="vvtCLAlterFuelTiming">"No"</constant>
<constant name="unused6-6">"MAP"</constant> <constant name="unused6-6">"MAP"</constant>
@ -710,7 +710,7 @@
<constant digits="0" name="ego_sdelay" units="sec">15.0</constant> <constant digits="0" name="ego_sdelay" units="sec">15.0</constant>
<constant digits="0" name="egoRPM" units="rpm">1200.0</constant> <constant digits="0" name="egoRPM" units="rpm">1200.0</constant>
<constant digits="0" name="egoTPSMax" units="%">70.0</constant> <constant digits="0" name="egoTPSMax" units="%">70.0</constant>
<constant name="vvtPin">"26"</constant> <constant name="vvt1Pin">"26"</constant>
<constant name="useExtBaro">"No"</constant> <constant name="useExtBaro">"No"</constant>
<constant name="boostMode">"Simple"</constant> <constant name="boostMode">"Simple"</constant>
<constant name="boostPin">"20"</constant> <constant name="boostPin">"20"</constant>

View File

@ -651,7 +651,7 @@
<constant digits="0" name="egoCount">16.0</constant> <constant digits="0" name="egoCount">16.0</constant>
<constant name="vvtMode">"Closed loop"</constant> <constant name="vvtMode">"Closed loop"</constant>
<constant name="vvtLoadSource">"MAP"</constant> <constant name="vvtLoadSource">"MAP"</constant>
<constant name="vvtCLDir">"Advance"</constant> <constant name="vvtPWMdir">"Advance"</constant>
<constant name="vvtCLUseHold">"No"</constant> <constant name="vvtCLUseHold">"No"</constant>
<constant name="vvtCLAlterFuelTiming">"Yes"</constant> <constant name="vvtCLAlterFuelTiming">"Yes"</constant>
<constant name="unused6-6">"MAP"</constant> <constant name="unused6-6">"MAP"</constant>
@ -661,7 +661,7 @@
<constant digits="0" name="ego_sdelay" units="sec">15.0</constant> <constant digits="0" name="ego_sdelay" units="sec">15.0</constant>
<constant digits="0" name="egoRPM" units="rpm">1200.0</constant> <constant digits="0" name="egoRPM" units="rpm">1200.0</constant>
<constant digits="0" name="egoTPSMax" units="%">70.0</constant> <constant digits="0" name="egoTPSMax" units="%">70.0</constant>
<constant name="vvtPin">"Board Default"</constant> <constant name="vvt1Pin">"Board Default"</constant>
<constant name="useExtBaro">"No"</constant> <constant name="useExtBaro">"No"</constant>
<constant name="boostMode">"Simple"</constant> <constant name="boostMode">"Simple"</constant>
<constant name="boostPin">"Board Default"</constant> <constant name="boostPin">"Board Default"</constant>

View File

@ -835,7 +835,7 @@
<constant digits="0" name="ego_sdelay" units="sec">15.0</constant> <constant digits="0" name="ego_sdelay" units="sec">15.0</constant>
<constant digits="0" name="egoRPM" units="rpm">1200.0</constant> <constant digits="0" name="egoRPM" units="rpm">1200.0</constant>
<constant digits="0" name="egoTPSMax" units="%">70.0</constant> <constant digits="0" name="egoTPSMax" units="%">70.0</constant>
<constant name="vvtPin">"Board Default"</constant> <constant name="vvt1Pin">"Board Default"</constant>
<constant name="useExtBaro">"No"</constant> <constant name="useExtBaro">"No"</constant>
<constant name="boostMode">"Simple"</constant> <constant name="boostMode">"Simple"</constant>
<constant name="boostPin">"Board Default"</constant> <constant name="boostPin">"Board Default"</constant>

View File

@ -842,7 +842,7 @@
<constant digits="0" name="egoCount">16.0</constant> <constant digits="0" name="egoCount">16.0</constant>
<constant name="vvtMode">"On/Off"</constant> <constant name="vvtMode">"On/Off"</constant>
<constant name="vvtLoadSource">"MAP"</constant> <constant name="vvtLoadSource">"MAP"</constant>
<constant name="vvtCLDir">"Advance"</constant> <constant name="vvtPWMdir">"Advance"</constant>
<constant name="vvtCLUseHold">"No"</constant> <constant name="vvtCLUseHold">"No"</constant>
<constant name="vvtCLAlterFuelTiming">"No"</constant> <constant name="vvtCLAlterFuelTiming">"No"</constant>
<constant name="unused6-6">"MAP"</constant> <constant name="unused6-6">"MAP"</constant>
@ -852,7 +852,7 @@
<constant digits="0" name="ego_sdelay" units="sec">15.0</constant> <constant digits="0" name="ego_sdelay" units="sec">15.0</constant>
<constant digits="0" name="egoRPM" units="rpm">1200.0</constant> <constant digits="0" name="egoRPM" units="rpm">1200.0</constant>
<constant digits="0" name="egoTPSMax" units="%">70.0</constant> <constant digits="0" name="egoTPSMax" units="%">70.0</constant>
<constant name="vvtPin">"Board Default"</constant> <constant name="vvt1Pin">"Board Default"</constant>
<constant name="useExtBaro">"No"</constant> <constant name="useExtBaro">"No"</constant>
<constant name="boostMode">"Simple"</constant> <constant name="boostMode">"Simple"</constant>
<constant name="boostPin">"Board Default"</constant> <constant name="boostPin">"Board Default"</constant>

View File

@ -541,7 +541,7 @@ page = 6
egoCount = scalar, U08, 5, "", 4.0, 0.0, 4.0, 255.0, 0 ; * ( 1 byte) egoCount = scalar, U08, 5, "", 4.0, 0.0, 4.0, 255.0, 0 ; * ( 1 byte)
vvtMode = bits, U08, 6, [0:1], "On/Off", "Open Loop", "Closed loop", "INVALID" vvtMode = bits, U08, 6, [0:1], "On/Off", "Open Loop", "Closed loop", "INVALID"
vvtLoadSource = bits, U08, 6, [2:3], "MAP", "TPS", "INVALID", "INVALID" vvtLoadSource = bits, U08, 6, [2:3], "MAP", "TPS", "INVALID", "INVALID"
vvtCLDir = bits, U08, 6, [4:4], "Advance", "Retard" vvtPWMdir = bits, U08, 6, [4:4], "Advance", "Retard"
vvtCLUseHold = bits, U08, 6, [5:5], "No", "Yes" vvtCLUseHold = bits, U08, 6, [5:5], "No", "Yes"
vvtCLAlterFuelTiming = bits, U08, 6, [6:6], "No", "Yes" vvtCLAlterFuelTiming = bits, U08, 6, [6:6], "No", "Yes"
boostCutEnabled = bits, U08, 6, [7:7], "Off", "On" boostCutEnabled = bits, U08, 6, [7:7], "Off", "On"
@ -551,7 +551,7 @@ page = 6
ego_sdelay = scalar, U08, 10, "sec", 1, 0, 0, 120, 0 ego_sdelay = scalar, U08, 10, "sec", 1, 0, 0, 120, 0
egoRPM = scalar, U08, 11, "rpm", 100, 0.0, 100, 25500, 0 egoRPM = scalar, U08, 11, "rpm", 100, 0.0, 100, 25500, 0
egoTPSMax = scalar, U08, 12, "%", 1, 0, 0, 120, 0 egoTPSMax = scalar, U08, 12, "%", 1, 0, 0, 120, 0
vvtPin = bits , U08, 13, [0:5], "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", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID" vvt1Pin = bits , U08, 13, [0:5], "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", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID"
useExtBaro = bits, U08, 13, [6:6], "No", "Yes" useExtBaro = bits, U08, 13, [6:6], "No", "Yes"
boostMode = bits, U08, 13, [7:7], "Simple", "Full" boostMode = bits, U08, 13, [7:7], "Simple", "Full"
boostPin = bits, U08, 14, [0:5], "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", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID" boostPin = bits, U08, 14, [0:5], "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", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID"
@ -1027,8 +1027,8 @@ page = 10
vvtCLKP = scalar, U08, 127, "%", 0.03125, 0.0, 0.0, 7.96, 2 ; * ( 1 byte) vvtCLKP = scalar, U08, 127, "%", 0.03125, 0.0, 0.0, 7.96, 2 ; * ( 1 byte)
vvtCLKI = scalar, U08, 128, "%", 0.03125, 0.0, 0.0, 7.96, 2 ; * ( 1 byte) vvtCLKI = scalar, U08, 128, "%", 0.03125, 0.0, 0.0, 7.96, 2 ; * ( 1 byte)
vvtCLKD = scalar, U08, 129, "%", 0.00781, 0.0, 0.0, 1.99, 3 ; * ( 1 byte) vvtCLKD = scalar, U08, 129, "%", 0.00781, 0.0, 0.0, 1.99, 3 ; * ( 1 byte)
vvtCLMinAng = scalar, U16, 130, "deg", 1.0, 0.0, 0.0, 360.0, 0 ; * ( 1 bytes) vvtCLMinAng = scalar, S16, 130, "deg", 1.0, 0.0, -360.0, 360.0, 0 ; * ( 2 bytes)
vvtCLMaxAng = scalar, U16, 132, "deg", 1.0, 0.0, 0.0, 360.0, 0 ; * ( 1 bytes) vvtCLMaxAng = scalar, S16, 132, "deg", 1.0, 0.0, -360.0, 360.0, 0 ; * ( 2 bytes)
crankingEnrichTaper = scalar, U08, 134, "s", 0.1, 0.0, 0.0, 25.5, 1 crankingEnrichTaper = scalar, U08, 134, "s", 0.1, 0.0, 0.0, 25.5, 1
@ -1047,7 +1047,7 @@ page = 10
oilPressureProtRPM = array, U08, 141, [ 4], "RPM", 100.0, 0.0, 100.0, 25500, 0 oilPressureProtRPM = array, U08, 141, [ 4], "RPM", 100.0, 0.0, 100.0, 25500, 0
oilPressureProtMins = array, U08, 145, [ 4], "psi", 1.0, 0.0, 0.0, 255, 0 oilPressureProtMins = array, U08, 145, [ 4], "psi", 1.0, 0.0, 0.0, 255, 0
wmiEnabled = bits, U08, 149, [0:0], "Off", "On" wmiEnabled = bits, U08, 149, [0:0], "Off", "On"
wmiMode = bits, U08, 149, [1:2], "Simple", "Proportional", "Openloop", "Closedloop" wmiMode = bits, U08, 149, [1:2], "Simple", "Proportional", "Openloop", "Closedloop"
@ -1077,7 +1077,10 @@ page = 10
wmiAdvBins = array, U08, 159, [6], "kPa", 2.0, 0.0, 0.0, 511.0, 0 wmiAdvBins = array, U08, 159, [6], "kPa", 2.0, 0.0, 0.0, 511.0, 0
wmiAdvAdj = array, U08, 165, [6], "Deg", 1.0, -40, -40, 215.0, 0 wmiAdvAdj = array, U08, 165, [6], "Deg", 1.0, -40, -40, 215.0, 0
unused11_171_191 = array, U08, 171, [21], "RPM", 100.0, 0.0, 100, 25500, 0 vvtCLminDuty = scalar, U08, 172, "%", 1.0, 0.0, 0.0, 100.0, 0 ; Minimum and maximum duty cycles when using closed loop
vvtCLmaxDuty = scalar, U08, 173, "%", 1.0, 0.0, 0.0, 100.0, 0
unused11_174_191 = array, U08, 174, [19], "RPM", 100.0, 0.0, 100, 25500, 0
;Page 11 is the fuel map and axis bins only ;Page 11 is the fuel map and axis bins only
page = 11 page = 11
@ -1159,12 +1162,14 @@ page = 12
requiresPowerCycle = wmiIndicatorEnabled requiresPowerCycle = wmiIndicatorEnabled
requiresPowerCycle = wmiIndicatorPin requiresPowerCycle = wmiIndicatorPin
requiresPowerCycle = wmiIndicatorPolarity requiresPowerCycle = wmiIndicatorPolarity
requiresPowerCycle = vvtCLminDuty
requiresPowerCycle = vvtCLmaxDuty
requiresPowerCycle = caninput_sel0a requiresPowerCycle = caninput_sel0a
requiresPowerCycle = caninput_sel0b requiresPowerCycle = caninput_sel0b
requiresPowerCycle = caninput_sel1a requiresPowerCycle = caninput_sel1a
requiresPowerCycle = caninput_sel1b requiresPowerCycle = caninput_sel1b
requiresPowerCycle = caninput_sel2a requiresPowerCycle = caninput_sel2a
requiresPowerCycle = caninput_sel2b requiresPowerCycle = caninput_sel2b
requiresPowerCycle = caninput_sel3a requiresPowerCycle = caninput_sel3a
requiresPowerCycle = caninput_sel3b requiresPowerCycle = caninput_sel3b
@ -1258,10 +1263,12 @@ page = 12
defaultValue = crankingEnrichTaper, 0.1 defaultValue = crankingEnrichTaper, 0.1
defaultValue = boostCutEnabled, 1 defaultValue = boostCutEnabled, 1
defaultValue = primingDelay, 0.5 defaultValue = primingDelay, 0.5
defaultValue = vvtCLminDuty, 0
defaultValue = vvtCLmaxDuty, 80 ;80% is a completely arbitrary amount for the max duty cycle, but seems inline with most VVT documentation
;Default pins ;Default pins
defaultValue = fanPin, 0 defaultValue = fanPin, 0
defaultValue = vvtPin, 0 defaultValue = vvt1Pin, 0
defaultValue = launchPin, 0 defaultValue = launchPin, 0
defaultValue = boostPin, 0 defaultValue = boostPin, 0
defaultValue = fuelPumpPin, 0 defaultValue = fuelPumpPin, 0
@ -2590,7 +2597,6 @@ menuDialog = main
field = "D", boostKD, { boostEnabled && boostMode && boostType == 1 } field = "D", boostKD, { boostEnabled && boostMode && boostType == 1 }
dialog = vvtClosedLoop, "Closed loop" dialog = vvtClosedLoop, "Closed loop"
field = "Increased duty direction", vvtCLDir
field = "Hold duty used", vvtCLUseHold field = "Hold duty used", vvtCLUseHold
field = "Hold duty", vvtCLholdDuty, { vvtCLUseHold } field = "Hold duty", vvtCLholdDuty, { vvtCLUseHold }
field = "Adjust fuel timing", vvtCLAlterFuelTiming field = "Adjust fuel timing", vvtCLAlterFuelTiming
@ -2599,6 +2605,8 @@ menuDialog = main
field = "Proportional Gain", vvtCLKP field = "Proportional Gain", vvtCLKP
field = "Integral Gain", vvtCLKI field = "Integral Gain", vvtCLKI
field = "Differential Gain", vvtCLKD field = "Differential Gain", vvtCLKD
field = "Minimum valve duty", vvtCLminDuty, { vvtEnabled && vvtMode == 2 }
field = "Maximum valve duty", vvtCLmaxDuty, { vvtEnabled && vvtMode == 2 }
dialog = vvtSettings, "VVT Control" dialog = vvtSettings, "VVT Control"
@ -2607,8 +2615,9 @@ menuDialog = main
field = "#Please note that close loop is currently experimental for Miata patterns ONLY" field = "#Please note that close loop is currently experimental for Miata patterns ONLY"
field = "Load source", vvtLoadSource, { vvtEnabled } field = "Load source", vvtLoadSource, { vvtEnabled }
field = "Use VVT map as On / Off only", VVTasOnOff, { vvtEnabled && vvtMode != 2 } field = "Use VVT map as On / Off only", VVTasOnOff, { vvtEnabled && vvtMode != 2 }
field = "VVT output pin", vvtPin, { vvtEnabled } field = "VVT output pin", vvt1Pin, { vvtEnabled }
field = "VVT solenoid freq.", vvtFreq, { vvtEnabled } field = "VVT solenoid freq.", vvtFreq, { vvtEnabled }
field = "Increased duty direction", vvtPWMdir, { vvtEnabled }
panel = vvtClosedLoop, { vvtEnabled && vvtMode == 2 } panel = vvtClosedLoop, { vvtEnabled && vvtMode == 2 }
dialog = wmiSettings, "WMI Control" dialog = wmiSettings, "WMI Control"
@ -2622,7 +2631,7 @@ menuDialog = main
field = "WMI min IAT", wmiIAT, { wmiEnabled } field = "WMI min IAT", wmiIAT, { wmiEnabled }
field = "WMI offset", wmiOffset, { wmiEnabled && wmiMode == 3} field = "WMI offset", wmiOffset, { wmiEnabled && wmiMode == 3}
field = "" field = ""
field = "WMI PWM output pin", vvtPin, { wmiEnabled } field = "WMI PWM output pin", vvt1Pin, { wmiEnabled }
field = "WMI PWM freq.", vvtFreq, { wmiEnabled } field = "WMI PWM freq.", vvtFreq, { wmiEnabled }
field = "" field = ""
field = "WMI enabled output pin", wmiEnabledPin, { wmiEnabled } field = "WMI enabled output pin", wmiEnabledPin, { wmiEnabled }
@ -3315,7 +3324,7 @@ menuDialog = main
displayOnlyField = "tachoPin", tachoPin, {tachoDuration} displayOnlyField = "tachoPin", tachoPin, {tachoDuration}
displayOnlyField = "idleUpPin", idleUpPin, {idleUpEnabled} displayOnlyField = "idleUpPin", idleUpPin, {idleUpEnabled}
displayOnlyField = "launchPin", launchPin, {launchEnable} displayOnlyField = "launchPin", launchPin, {launchEnable}
displayOnlyField = "vvtPin", vvtPin, {vvtEnabled} displayOnlyField = "vvt1Pin", vvt1Pin, {vvtEnabled}
displayOnlyField = "vssPin", vssPin, {vssMode > 1} displayOnlyField = "vssPin", vssPin, {vssMode > 1}
displayOnlyField = "boostPin", boostPin, {boostEnabled} displayOnlyField = "boostPin", boostPin, {boostEnabled}
displayOnlyField = "baroPin", baroPin,{useExtBaro} displayOnlyField = "baroPin", baroPin,{useExtBaro}
@ -3851,9 +3860,15 @@ cmdVSSratio6 = "E\x99\x06"
boostDutyGauge = boostDuty, "Boost Duty Cycle", "%", 0, 100, -1, -1, 101, 110, 1, 1 boostDutyGauge = boostDuty, "Boost Duty Cycle", "%", 0, 100, -1, -1, 101, 110, 1, 1
afrTargetGauge = afrTarget, "Target AFR", "", 7, 25, 12, 13, 15, 16, 2, 2 afrTargetGauge = afrTarget, "Target AFR", "", 7, 25, 12, 13, 15, 16, 2, 2
lambdaTargetGauge = lambdaTarget, "Target Lambda", "", 0.5, 1.5, 0.82, 0.89, 1.02, 1.09, 3, 3 lambdaTargetGauge = lambdaTarget, "Target Lambda", "", 0.5, 1.5, 0.82, 0.89, 1.02, 1.09, 3, 3
VVTdutyCycleGauge = vvtDuty, "VVT Duty Cycle", "%", 0, 100, -1, -1, 101, 110, 1, 1
IdleTargetGauge = CLIdleTarget, "Idle Target RPM", "RPM", 0, 2000, 300, 600, 1500, 1700, 0, 0 IdleTargetGauge = CLIdleTarget, "Idle Target RPM", "RPM", 0, 2000, 300, 600, 1500, 1700, 0, 0
idleLoadGauge = idleLoad, "IAC Value", "%/Steps", 0, {maphigh}, 0, 20, {mapwarn}, {mapdang}, 0, 0 idleLoadGauge = idleLoad, "IAC Value", "%/Steps", 0, {maphigh}, 0, 20, {mapwarn}, {mapdang}, 0, 0
vvt1DutyCycleGauge= vvt1Duty, "VVT Duty Cycle", "%", 0, 100, -1, -1, 101, 110, 1, 1
vvt1TargetGauge = vvt1Target, "VVT Target Angle", "deg", 0, 100, 15, 25, 65, 75, 0, 0
vvt1AngleGauge = vvt1Angle, "VVT Angle", "deg", -20, 100, 0, -5, 70, 90, 0, 0
vvt2DutyCycleGauge= vvt2Duty, "VVT Duty Cycle", "%", 0, 100, -1, -1, 101, 110, 1, 1
vvt2TargetGauge = vvt2Target, "VVT Target Angle", "deg", 0, 100, 15, 25, 65, 75, 0, 0
vvt2AngleGauge = vvt2Angle, "VVT Angle", "deg", -20, 100, 0, -5, 70, 90, 0, 0
WMIdutyCycleGauge = wmiPW, "WMI Duty Cycle", "%", 0, 100, -1, -1, 101, 110, 1, 1 WMIdutyCycleGauge = wmiPW, "WMI Duty Cycle", "%", 0, 100, -1, -1, 101, 110, 1, 1
gaugeCategory = "Sensor inputs" gaugeCategory = "Sensor inputs"
@ -3970,7 +3985,7 @@ cmdVSSratio6 = "E\x99\x06"
ochGetCommand = "r\$tsCanId\x30%2o%2c" ochGetCommand = "r\$tsCanId\x30%2o%2c"
;ochBlockSize = 104 ;ochBlockSize = 104
ochBlockSize = 108 ochBlockSize = 111
secl = scalar, U08, 0, "sec", 1.000, 0.000 secl = scalar, U08, 0, "sec", 1.000, 0.000
status1 = scalar, U08, 1, "bits", 1.000, 0.000 status1 = scalar, U08, 1, "bits", 1.000, 0.000
@ -4076,9 +4091,9 @@ cmdVSSratio6 = "E\x99\x06"
dwell = scalar, U16, 89, "ms", 0.001, 0.000 dwell = scalar, U16, 89, "ms", 0.001, 0.000
CLIdleTarget = scalar, U08, 91, "RPM", 10.00, 0.000 CLIdleTarget = scalar, U08, 91, "RPM", 10.00, 0.000
MAPdot = scalar, U08, 92, "kPa/s", 10.00, 0.000 MAPdot = scalar, U08, 92, "kPa/s", 10.00, 0.000
vvtAngle = scalar, S08, 93, "deg", 1.00, 0.000 vvt1Angle = scalar, S08, 93, "deg", 1.00, 0.000
vvtTarget = scalar, U08, 94, "deg", 1.00, 0.000 vvt1Target = scalar, U08, 94, "deg", 1.00, 0.000
vvtDuty = scalar, U08, 95, "%", 1.00, 0.000 vvt1Duty = scalar, U08, 95, "%", 1.00, 0.000
flexBoostCor = scalar, S16, 96, "kPa", 1.000, 0.000 flexBoostCor = scalar, S16, 96, "kPa", 1.000, 0.000
baroCorrection = scalar, U08, 98, "%", 1.000, 0.000 baroCorrection = scalar, U08, 98, "%", 1.000, 0.000
veCurr = scalar, U08, 99, "%", 1.000, 0.000 veCurr = scalar, U08, 99, "%", 1.000, 0.000
@ -4090,6 +4105,9 @@ cmdVSSratio6 = "E\x99\x06"
wmiPW = scalar, U08, 106, "%", 1.000, 0.000 wmiPW = scalar, U08, 106, "%", 1.000, 0.000
wmiEmpty = scalar, U08, 107, "bits", 1.000, 0.000 wmiEmpty = scalar, U08, 107, "bits", 1.000, 0.000
wmiEmptyBit = bits, U08, 107, [0:0] wmiEmptyBit = bits, U08, 107, [0:0]
vvt2Angle = scalar, S08, 108, "deg", 1.00, 0.000
vvt2Target = scalar, U08, 109, "deg", 1.00, 0.000
vvt2Duty = scalar, U08, 110, "%", 1.00, 0.000
#sd_status = scalar, U08, 99, "", 1.0, 0.0 #sd_status = scalar, U08, 99, "", 1.0, 0.0
#if CELSIUS #if CELSIUS
@ -4214,13 +4232,16 @@ cmdVSSratio6 = "E\x99\x06"
entry = baro, "Baro Pressure",int, "%d" entry = baro, "Baro Pressure",int, "%d"
entry = nitrousOn, "Nitrous", int, "%d", { n2o_enable > 0 } entry = nitrousOn, "Nitrous", int, "%d", { n2o_enable > 0 }
entry = syncLossCounter, "Sync Loss #", int, "%d" entry = syncLossCounter, "Sync Loss #", int, "%d"
entry = vvtAngle, "VVT Angle", int, "%d", { vvtMode == 2 } ;;Only show when using close loop vvt entry = vvt1Angle, "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 = vvt1Target, "VVT Target Angle", int, "%d", { vvtMode == 2 } ;;Only show when using close loop vvt
entry = vvtDuty, "VVT Duty", int, "%d", { vvtEnabled > 0 } entry = vvt1Duty, "VVT Duty", int, "%d", { vvtEnabled > 0 }
entry = vss, "VSS (Speed)", int, "%d", { vssMode > 1 } entry = vss, "VSS (Speed)", int, "%d", { vssMode > 1 }
entry = gear, "Gear", int, "%d", { vssMode > 1 } entry = gear, "Gear", int, "%d", { vssMode > 1 }
entry = fuelPressure, "Fuel Pressure",int, "%d", { fuelPressureEnable > 0 } entry = fuelPressure, "Fuel Pressure",int, "%d", { fuelPressureEnable > 0 }
entry = oilPressure, "Oil Pressure", int, "%d", { oilPressureEnable > 0 } entry = oilPressure, "Oil Pressure", int, "%d", { oilPressureEnable > 0 }
entry = vvt2Angle, "VVT Angle", int, "%d", { vvtMode == 2 } ;;Only show when using close loop vvt
entry = vvt2Target, "VVT Target Angle", int, "%d", { vvtMode == 2 } ;;Only show when using close loop vvt
entry = vvt2Duty, "VVT Duty", int, "%d", { vvtEnabled > 0 }
entry = auxin_gauge0, { stringValue(AUXin00Alias)}, int, "%d", {(caninput_sel0b != 0)} entry = auxin_gauge0, { stringValue(AUXin00Alias)}, int, "%d", {(caninput_sel0b != 0)}
entry = auxin_gauge1, { stringValue(AUXin01Alias)}, int, "%d", { (caninput_sel1b != 0)} entry = auxin_gauge1, { stringValue(AUXin01Alias)}, int, "%d", { (caninput_sel1b != 0)}

View File

@ -19,8 +19,10 @@ void wmiControl();
#define BOOST_PIN_LOW() *boost_pin_port &= ~(boost_pin_mask) #define BOOST_PIN_LOW() *boost_pin_port &= ~(boost_pin_mask)
#define BOOST_PIN_HIGH() *boost_pin_port |= (boost_pin_mask) #define BOOST_PIN_HIGH() *boost_pin_port |= (boost_pin_mask)
#define VVT_PIN_LOW() *vvt_pin_port &= ~(vvt_pin_mask) #define VVT1_PIN_LOW() *vvt1_pin_port &= ~(vvt1_pin_mask)
#define VVT_PIN_HIGH() *vvt_pin_port |= (vvt_pin_mask) #define VVT1_PIN_HIGH() *vvt1_pin_port |= (vvt1_pin_mask)
#define VVT2_PIN_LOW() *vvt2_pin_port &= ~(vvt2_pin_mask)
#define VVT2_PIN_HIGH() *vvt2_pin_port |= (vvt2_pin_mask)
#define FAN_PIN_LOW() *fan_pin_port &= ~(fan_pin_mask) #define FAN_PIN_LOW() *fan_pin_port &= ~(fan_pin_mask)
#define FAN_PIN_HIGH() *fan_pin_port |= (fan_pin_mask) #define FAN_PIN_HIGH() *fan_pin_port |= (fan_pin_mask)
#define N2O_STAGE1_PIN_LOW() *n2o_stage1_pin_port &= ~(n2o_stage1_pin_mask) #define N2O_STAGE1_PIN_LOW() *n2o_stage1_pin_port &= ~(n2o_stage1_pin_mask)
@ -36,8 +38,10 @@ void wmiControl();
volatile PORT_TYPE *boost_pin_port; volatile PORT_TYPE *boost_pin_port;
volatile PINMASK_TYPE boost_pin_mask; volatile PINMASK_TYPE boost_pin_mask;
volatile PORT_TYPE *vvt_pin_port; volatile PORT_TYPE *vvt1_pin_port;
volatile PINMASK_TYPE vvt_pin_mask; volatile PINMASK_TYPE vvt1_pin_mask;
volatile PORT_TYPE *vvt2_pin_port;
volatile PINMASK_TYPE vvt2_pin_mask;
volatile PORT_TYPE *fan_pin_port; volatile PORT_TYPE *fan_pin_port;
volatile PINMASK_TYPE fan_pin_mask; volatile PINMASK_TYPE fan_pin_mask;
volatile PORT_TYPE *n2o_stage1_pin_port; volatile PORT_TYPE *n2o_stage1_pin_port;
@ -58,10 +62,16 @@ byte vvtCounter;
byte fanHIGH = HIGH; // Used to invert the cooling fan output byte fanHIGH = HIGH; // Used to invert the cooling fan output
byte fanLOW = LOW; // Used to invert the cooling fan output byte fanLOW = LOW; // Used to invert the cooling fan output
volatile bool vvt_pwm_state; volatile bool vvt1_pwm_state;
volatile bool vvt2_pwm_state;
volatile bool vvt1_max_pwm;
volatile bool vvt2_max_pwm;
volatile char nextVVT;
unsigned int vvt_pwm_max_count; //Used for variable PWM frequency unsigned int vvt_pwm_max_count; //Used for variable PWM frequency
volatile unsigned int vvt_pwm_cur_value; volatile unsigned int vvt1_pwm_cur_value;
long vvt_pwm_value; volatile unsigned int vvt2_pwm_cur_value;
long vvt1_pwm_value;
long vvt2_pwm_value;
long vvt_pid_target_angle; long vvt_pid_target_angle;
//long vvt_pid_current_angle; //long vvt_pid_current_angle;
static inline void boostInterrupt(); static inline void boostInterrupt();

View File

@ -12,7 +12,7 @@ A full copy of the license may be found in the projects root directory
//Old PID method. Retained incase the new one has issues //Old PID method. Retained incase the new one has issues
//integerPID boostPID(&MAPx100, &boost_pwm_target_value, &boostTargetx100, configPage6.boostKP, configPage6.boostKI, configPage6.boostKD, DIRECT); //integerPID boostPID(&MAPx100, &boost_pwm_target_value, &boostTargetx100, configPage6.boostKP, configPage6.boostKI, configPage6.boostKD, DIRECT);
integerPID_ideal boostPID(&currentStatus.MAP, &currentStatus.boostDuty , &currentStatus.boostTarget, &configPage10.boostSens, &configPage10.boostIntv, configPage6.boostKP, configPage6.boostKI, configPage6.boostKD, DIRECT); //This is the PID object if that algorithm is used. Needs to be global as it maintains state outside of each function call integerPID_ideal boostPID(&currentStatus.MAP, &currentStatus.boostDuty , &currentStatus.boostTarget, &configPage10.boostSens, &configPage10.boostIntv, configPage6.boostKP, configPage6.boostKI, configPage6.boostKD, DIRECT); //This is the PID object if that algorithm is used. Needs to be global as it maintains state outside of each function call
integerPID vvtPID(&currentStatus.vvtAngle, &vvt_pwm_value, &vvt_pid_target_angle, configPage10.vvtCLKP, configPage10.vvtCLKI, configPage10.vvtCLKD, DIRECT); //This is the PID object if that algorithm is used. Needs to be global as it maintains state outside of each function call integerPID vvtPID(&currentStatus.vvt1Angle, &vvt1_pwm_value, &vvt_pid_target_angle, configPage10.vvtCLKP, configPage10.vvtCLKI, configPage10.vvtCLKD, DIRECT); //This is the PID object if that algorithm is used. Needs to be global as it maintains state outside of each function call
/* /*
Fan control Fan control
@ -66,8 +66,10 @@ void initialiseAuxPWM()
{ {
boost_pin_port = portOutputRegister(digitalPinToPort(pinBoost)); boost_pin_port = portOutputRegister(digitalPinToPort(pinBoost));
boost_pin_mask = digitalPinToBitMask(pinBoost); boost_pin_mask = digitalPinToBitMask(pinBoost);
vvt_pin_port = portOutputRegister(digitalPinToPort(pinVVT_1)); vvt1_pin_port = portOutputRegister(digitalPinToPort(pinVVT_1));
vvt_pin_mask = digitalPinToBitMask(pinVVT_1); vvt1_pin_mask = digitalPinToBitMask(pinVVT_1);
vvt2_pin_port = portOutputRegister(digitalPinToPort(pinVVT_2));
vvt2_pin_mask = digitalPinToBitMask(pinVVT_2);
n2o_stage1_pin_port = portOutputRegister(digitalPinToPort(configPage10.n2o_stage1_pin)); n2o_stage1_pin_port = portOutputRegister(digitalPinToPort(configPage10.n2o_stage1_pin));
n2o_stage1_pin_mask = digitalPinToBitMask(configPage10.n2o_stage1_pin); n2o_stage1_pin_mask = digitalPinToBitMask(configPage10.n2o_stage1_pin);
n2o_stage2_pin_port = portOutputRegister(digitalPinToPort(configPage10.n2o_stage2_pin)); n2o_stage2_pin_port = portOutputRegister(digitalPinToPort(configPage10.n2o_stage2_pin));
@ -92,7 +94,8 @@ void initialiseAuxPWM()
if( configPage6.vvtEnabled > 0) if( configPage6.vvtEnabled > 0)
{ {
currentStatus.vvtAngle = 0; currentStatus.vvt1Angle = 0;
currentStatus.vvt2Angle = 0;
#if defined(CORE_AVR) #if defined(CORE_AVR)
vvt_pwm_max_count = 1000000L / (16 * configPage6.vvtFreq * 2); //Converts the frequency in Hz to the number of ticks (at 16uS) it takes to complete 1 cycle. Note that the frequency is divided by 2 coming from TS to allow for up to 512hz vvt_pwm_max_count = 1000000L / (16 * configPage6.vvtFreq * 2); //Converts the frequency in Hz to the number of ticks (at 16uS) it takes to complete 1 cycle. Note that the frequency is divided by 2 coming from TS to allow for up to 512hz
@ -102,16 +105,19 @@ void initialiseAuxPWM()
if(configPage6.vvtMode == VVT_MODE_CLOSED_LOOP) if(configPage6.vvtMode == VVT_MODE_CLOSED_LOOP)
{ {
vvtPID.SetOutputLimits(0, percentage(80, vvt_pwm_max_count)); //80% is a completely arbitrary amount for the max duty cycle, but seems inline with most VVT documentation vvtPID.SetOutputLimits(percentage(configPage10.vvtCLminDuty, vvt_pwm_max_count), percentage(configPage10.vvtCLmaxDuty, vvt_pwm_max_count));
vvtPID.SetTunings(configPage10.vvtCLKP, configPage10.vvtCLKI, configPage10.vvtCLKD); vvtPID.SetTunings(configPage10.vvtCLKP, configPage10.vvtCLKI, configPage10.vvtCLKD);
vvtPID.SetSampleTime(30); vvtPID.SetSampleTime(33); //30Hz is 33,33ms
vvtPID.SetMode(AUTOMATIC); //Turn PID on vvtPID.SetMode(AUTOMATIC); //Turn PID on
} }
currentStatus.vvtDuty = 0; currentStatus.vvt1Duty = 0;
vvt_pwm_value = 0; vvt1_pwm_value = 0;
currentStatus.vvt2Duty = 0;
vvt2_pwm_value = 0;
ENABLE_VVT_TIMER(); //Turn on the B compare unit (ie turn on the interrupt)
} }
if(configPage6.vvtEnabled == 0 && configPage10.wmiEnabled >= 1) if( (configPage6.vvtEnabled == 0) && (configPage10.wmiEnabled >= 1) )
{ {
// config wmi pwm output to use vvt output // config wmi pwm output to use vvt output
#if defined(CORE_AVR) #if defined(CORE_AVR)
@ -121,13 +127,14 @@ void initialiseAuxPWM()
#endif #endif
currentStatus.wmiEmpty = 0; currentStatus.wmiEmpty = 0;
currentStatus.wmiPW = 0; currentStatus.wmiPW = 0;
vvt_pwm_value = 0; vvt1_pwm_value = 0;
ENABLE_VVT_TIMER(); //Turn on the B compare unit (ie turn on the interrupt)
} }
ENABLE_VVT_TIMER(); //Turn on the B compare unit (ie turn on the interrupt)
currentStatus.boostDuty = 0; currentStatus.boostDuty = 0;
boostCounter = 0; boostCounter = 0;
currentStatus.vvtDuty = 0; currentStatus.vvt1Duty = 0;
currentStatus.vvt2Duty = 0;
vvtCounter = 0; vvtCounter = 0;
currentStatus.nitrous_status = NITROUS_OFF; currentStatus.nitrous_status = NITROUS_OFF;
@ -215,89 +222,79 @@ void vvtControl()
{ {
if( (configPage6.vvtEnabled == 1) && (currentStatus.RPM > 0) ) if( (configPage6.vvtEnabled == 1) && (currentStatus.RPM > 0) )
{ {
currentStatus.vvtDuty = 0; //currentStatus.vvt1Duty = 0;
//Calculate the current cam angle
if( configPage4.TrigPattern == 9 ) { getCamAngle_Miata9905(); }
if( (configPage6.vvtMode == VVT_MODE_OPEN_LOOP) || (configPage6.vvtMode == VVT_MODE_ONOFF) ) if( (configPage6.vvtMode == VVT_MODE_OPEN_LOOP) || (configPage6.vvtMode == VVT_MODE_ONOFF) )
{ {
//Lookup VVT duty based on either MAP or TPS //Lookup VVT duty based on either MAP or TPS
if(configPage6.vvtLoadSource == VVT_LOAD_TPS) if(configPage6.vvtLoadSource == VVT_LOAD_TPS) { currentStatus.vvt1Duty = get3DTableValue(&vvtTable, currentStatus.TPS, currentStatus.RPM); }
{ else { currentStatus.vvt1Duty = get3DTableValue(&vvtTable, currentStatus.MAP, currentStatus.RPM); }
currentStatus.vvtDuty = get3DTableValue(&vvtTable, currentStatus.TPS, currentStatus.RPM);
}
else
{
currentStatus.vvtDuty = get3DTableValue(&vvtTable, currentStatus.MAP, currentStatus.RPM);
}
//VVT table can be used for controlling on/off switching. If this is turned on, then disregard any interpolation or non-binary values //VVT table can be used for controlling on/off switching. If this is turned on, then disregard any interpolation or non-binary values
if( (configPage6.VVTasOnOff == true) && (currentStatus.vvtDuty < 100) ) { currentStatus.vvtDuty = 0; } if( (configPage6.VVTasOnOff == true) && (currentStatus.vvt1Duty < 100) ) { currentStatus.vvt1Duty = 0; }
vvt_pwm_value = percentage(currentStatus.vvtDuty, vvt_pwm_max_count); vvt1_pwm_value = percentage(currentStatus.vvt1Duty, vvt_pwm_max_count);
if(currentStatus.vvtDuty > 0) { ENABLE_VVT_TIMER(); } if(currentStatus.vvt1Duty > 0) { ENABLE_VVT_TIMER(); }
} //Open loop } //Open loop
else if( (configPage6.vvtMode == VVT_MODE_CLOSED_LOOP) ) else if( (configPage6.vvtMode == VVT_MODE_CLOSED_LOOP) )
{ {
//Calculate the current cam angle
getCamAngle_Miata9905();
//Lookup VVT duty based on either MAP or TPS //Lookup VVT duty based on either MAP or TPS
if(configPage6.vvtLoadSource == VVT_LOAD_TPS) if(configPage6.vvtLoadSource == VVT_LOAD_TPS) { currentStatus.vvt1TargetAngle = get3DTableValue(&vvtTable, currentStatus.TPS, currentStatus.RPM); }
{ else { currentStatus.vvt1TargetAngle = get3DTableValue(&vvtTable, currentStatus.MAP, currentStatus.RPM); }
currentStatus.vvtTargetAngle = get3DTableValue(&vvtTable, currentStatus.TPS, currentStatus.RPM);
}
else
{
currentStatus.vvtTargetAngle = get3DTableValue(&vvtTable, currentStatus.MAP, currentStatus.RPM);
}
if( (vvtCounter & 31) == 1) { vvtPID.SetTunings(configPage10.vvtCLKP, configPage10.vvtCLKI, configPage10.vvtCLKD); } //This only needs to be run very infrequently, once every 32 calls to vvtControl(). This is approx. once per second if( (vvtCounter & 31) == 1) { vvtPID.SetTunings(configPage10.vvtCLKP, configPage10.vvtCLKI, configPage10.vvtCLKD); } //This only needs to be run very infrequently, once every 32 calls to vvtControl(). This is approx. once per second
//Check that we're not already at the angle we want to be //Check that we're not already at the angle we want to be
if((configPage6.vvtCLUseHold > 0) && (currentStatus.vvtTargetAngle == currentStatus.vvtAngle) ) if((configPage6.vvtCLUseHold > 0) && (currentStatus.vvt1TargetAngle == currentStatus.vvt1Angle) )
{ {
currentStatus.vvtDuty = configPage10.vvtCLholdDuty; currentStatus.vvt1Duty = configPage10.vvtCLholdDuty;
vvt_pwm_value = percentage(currentStatus.vvtDuty, vvt_pwm_max_count); vvt1_pwm_value = percentage(currentStatus.vvt1Duty, vvt_pwm_max_count);
vvtPID.Initialize(); vvtPID.Initialize();
} }
else else
{ {
//If not already at target angle, calculate new value from PID
//This is dumb, but need to convert the current angle into a long pointer //This is dumb, but need to convert the current angle into a long pointer
vvt_pid_target_angle = currentStatus.vvtTargetAngle; vvt_pid_target_angle = currentStatus.vvt1TargetAngle;
if(currentStatus.vvtTargetAngle > 0) if(currentStatus.vvt1TargetAngle >= 0)
{ {
//If not already at target angle, calculate new value from PID
bool PID_compute = vvtPID.Compute(false); bool PID_compute = vvtPID.Compute(false);
//vvtPID.Compute2(currentStatus.vvtTargetAngle, currentStatus.vvtAngle, false); //vvtPID.Compute2(currentStatus.vvt1TargetAngle, currentStatus.vvt1Angle, false);
//vvt_pwm_target_value = percentage(40, vvt_pwm_max_count); //vvt_pwm_target_value = percentage(40, vvt_pwm_max_count);
//if (currentStatus.vvtAngle > currentStatus.vvtTargetAngle) { vvt_pwm_target_value = 0; } //if (currentStatus.vvt1Angle > currentStatus.vvt1TargetAngle) { vvt_pwm_target_value = 0; }
if(PID_compute == true) { currentStatus.vvtDuty = (vvt_pwm_value * 100) / vvt_pwm_max_count; } if(PID_compute == true) { currentStatus.vvt1Duty = (vvt1_pwm_value * 100) / vvt_pwm_max_count; }
}
else
{
currentStatus.vvtDuty = 0;
} }
else { currentStatus.vvt1Duty = 0; }
} }
if(currentStatus.vvtDuty > 0) { ENABLE_VVT_TIMER(); } if( (currentStatus.vvt1Duty > 0) || (currentStatus.vvt2Duty > 0) ) { ENABLE_VVT_TIMER(); }
//currentStatus.vvtDuty = 0; //currentStatus.vvt1Duty = 0;
vvtCounter++; vvtCounter++;
} }
//Set the PWM state based on the above lookups //Set the PWM state based on the above lookups
if(currentStatus.vvtDuty == 0) if( (currentStatus.vvt1Duty == 0) && (currentStatus.vvt2Duty == 0) )
{ {
//Make sure solenoid is off (0% duty) //Make sure solenoid is off (0% duty)
VVT_PIN_LOW(); if (configPage6.vvtPWMdir == 0) { *vvt1_pin_port &= ~(vvt1_pin_mask); } //Normal direction
else { *vvt1_pin_port |= (vvt1_pin_mask); } //Reversed direction
if (configPage6.vvtPWMdir == 0) { *vvt2_pin_port &= ~(vvt2_pin_mask); } //Normal direction
else { *vvt2_pin_port |= (vvt2_pin_mask); } //Reversed direction
DISABLE_VVT_TIMER(); DISABLE_VVT_TIMER();
} }
else if (currentStatus.vvtDuty >= 100) else if( (currentStatus.vvt1Duty >= 100) && (currentStatus.vvt2Duty >= 100) )
{ {
//Make sure solenoid is on (100% duty) //Make sure solenoid is on (100% duty)
VVT_PIN_HIGH(); if (configPage6.vvtPWMdir == 0) { *vvt1_pin_port |= (vvt1_pin_mask); } //Normal direction
else { *vvt1_pin_port &= ~(vvt1_pin_mask); } //Reversed direction
if (configPage6.vvtPWMdir == 0) { *vvt2_pin_port |= (vvt2_pin_mask); } //Normal direction
else { *vvt2_pin_port &= ~(vvt2_pin_mask); } //Reversed direction
DISABLE_VVT_TIMER(); DISABLE_VVT_TIMER();
} }
@ -306,8 +303,10 @@ void vvtControl()
{ {
// Disable timer channel // Disable timer channel
DISABLE_VVT_TIMER(); DISABLE_VVT_TIMER();
currentStatus.vvtDuty = 0; currentStatus.vvt1Duty = 0;
vvt_pwm_value = 0; vvt1_pwm_value = 0;
currentStatus.vvt2Duty = 0;
vvt2_pwm_value = 0;
} }
} }
@ -407,12 +406,12 @@ void wmiControl()
} }
currentStatus.wmiPW = wmiPW; currentStatus.wmiPW = wmiPW;
vvt_pwm_value = wmiPW; vvt1_pwm_value = wmiPW;
if(wmiPW == 0) if(wmiPW == 0)
{ {
// Make sure water pump is off // Make sure water pump is off
VVT_PIN_LOW(); VVT1_PIN_LOW();
DISABLE_VVT_TIMER(); DISABLE_VVT_TIMER();
digitalWrite(pinWMIEnabled, LOW); digitalWrite(pinWMIEnabled, LOW);
} }
@ -422,7 +421,7 @@ void wmiControl()
if (wmiPW >= 100) if (wmiPW >= 100)
{ {
// Make sure water pump is on (100% duty) // Make sure water pump is on (100% duty)
VVT_PIN_HIGH(); VVT1_PIN_HIGH();
DISABLE_VVT_TIMER(); DISABLE_VVT_TIMER();
} }
else else
@ -470,17 +469,96 @@ void boostDisable()
static inline void vvtInterrupt() //Most ARM chips can simply call a function static inline void vvtInterrupt() //Most ARM chips can simply call a function
#endif #endif
{ {
if (vvt_pwm_state == true) if ( ((vvt1_pwm_state == false) || (vvt1_max_pwm == true)) && ((vvt2_pwm_state == false) || (vvt2_max_pwm == true)) )
{ {
VVT_PIN_LOW(); // Switch pin to low if( (vvt1_pwm_value > 0) && (vvt1_max_pwm == false) ) //Don't toggle if at 0%
VVT_TIMER_COMPARE = VVT_TIMER_COUNTER + (vvt_pwm_max_count - vvt_pwm_cur_value); {
vvt_pwm_state = false; if (configPage6.vvtPWMdir == 0) { *vvt1_pin_port |= (vvt1_pin_mask); } //Normal direction
else { *vvt1_pin_port &= ~(vvt1_pin_mask); } //Reversed direction
vvt1_pwm_state = true;
}
if( (vvt2_pwm_value > 0) && (vvt2_max_pwm == false) ) //Don't toggle if at 0%
{
if (configPage6.vvtPWMdir == 0) { *vvt2_pin_port |= (vvt2_pin_mask); } //Normal direction
else { *vvt2_pin_port &= ~(vvt2_pin_mask); } //Reversed direction
vvt2_pwm_state = true;
}
if( (vvt1_pwm_state == true) && (vvt1_pwm_value <= vvt2_pwm_value) )
{
VVT_TIMER_COMPARE = VVT_TIMER_COUNTER + vvt1_pwm_value;
vvt1_pwm_cur_value = vvt1_pwm_value;
vvt2_pwm_cur_value = vvt2_pwm_value;
if (vvt1_pwm_value == vvt2_pwm_value) { nextVVT = 2; } //Next event is for both PWM
else { nextVVT = 0; } //Next event is for PWM0
}
else if( vvt2_pwm_state == true )
{
VVT_TIMER_COMPARE = VVT_TIMER_COUNTER + vvt2_pwm_value;
vvt1_pwm_cur_value = vvt1_pwm_value;
vvt2_pwm_cur_value = vvt2_pwm_value;
nextVVT = 1; //Next event is for PWM1
}
else { VVT_TIMER_COMPARE = VVT_TIMER_COUNTER + vvt_pwm_max_count; } //Shouldn't ever get here
} }
else else
{ {
VVT_PIN_HIGH(); // Switch pin high if(nextVVT == 0)
VVT_TIMER_COMPARE = VVT_TIMER_COUNTER + vvt_pwm_value; {
vvt_pwm_cur_value = vvt_pwm_value; if(vvt1_pwm_value < vvt_pwm_max_count) //Don't toggle if at 100%
vvt_pwm_state = true; {
if (configPage6.vvtPWMdir == 0) { *vvt1_pin_port &= ~(vvt1_pin_mask); } //Normal direction
else { *vvt1_pin_port |= (vvt1_pin_mask); } //Reversed direction
vvt1_pwm_state = false;
vvt1_max_pwm = false;
}
else { vvt1_max_pwm = true; }
nextVVT = 1; //Next event is for PWM1
if(vvt2_pwm_state == true){ VVT_TIMER_COMPARE = VVT_TIMER_COUNTER + (vvt2_pwm_cur_value - vvt1_pwm_cur_value); }
else
{
VVT_TIMER_COMPARE = VVT_TIMER_COUNTER + (vvt_pwm_max_count - vvt1_pwm_cur_value);
nextVVT = 2; //Next event is for both PWM
}
}
else if (nextVVT == 1)
{
if(vvt2_pwm_value < vvt_pwm_max_count) //Don't toggle if at 100%
{
if (configPage6.vvtPWMdir == 0) { *vvt2_pin_port &= ~(vvt2_pin_mask); } //Normal direction
else { *vvt2_pin_port |= (vvt2_pin_mask); } //Reversed direction
vvt2_pwm_state = false;
vvt2_max_pwm = false;
}
else { vvt2_max_pwm = true; }
nextVVT = 0; //Next event is for PWM0
if(vvt1_pwm_state == true) { VVT_TIMER_COMPARE = VVT_TIMER_COUNTER + (vvt1_pwm_cur_value - vvt2_pwm_cur_value); }
else
{
VVT_TIMER_COMPARE = VVT_TIMER_COUNTER + (vvt_pwm_max_count - vvt2_pwm_cur_value);
nextVVT = 2; //Next event is for both PWM
}
}
else
{
if(vvt1_pwm_value < vvt_pwm_max_count) //Don't toggle if at 100%
{
if (configPage6.vvtPWMdir == 0) { *vvt1_pin_port &= ~(vvt1_pin_mask); } //Normal direction
else { *vvt1_pin_port |= (vvt1_pin_mask); } //Reversed direction
vvt1_pwm_state = false;
vvt1_max_pwm = false;
VVT_TIMER_COMPARE = VVT_TIMER_COUNTER + (vvt_pwm_max_count - vvt1_pwm_cur_value);
}
else { vvt1_max_pwm = true; }
if(vvt2_pwm_value < vvt_pwm_max_count) //Don't toggle if at 100%
{
if (configPage6.vvtPWMdir == 0) { *vvt2_pin_port &= ~(vvt2_pin_mask); } //Normal direction
else { *vvt2_pin_port |= (vvt2_pin_mask); } //Reversed direction
vvt2_pwm_state = false;
vvt2_max_pwm = false;
VVT_TIMER_COMPARE = VVT_TIMER_COUNTER + (vvt_pwm_max_count - vvt2_pwm_cur_value);
}
else { vvt2_max_pwm = true; }
}
} }
} }

View File

@ -638,9 +638,9 @@ void sendValues(uint16_t offset, uint16_t packetLength, byte cmd, byte portNum)
fullStatus[90] = highByte(currentStatus.dwell); fullStatus[90] = highByte(currentStatus.dwell);
fullStatus[91] = currentStatus.CLIdleTarget; fullStatus[91] = currentStatus.CLIdleTarget;
fullStatus[92] = currentStatus.mapDOT; fullStatus[92] = currentStatus.mapDOT;
fullStatus[93] = (int8_t)currentStatus.vvtAngle; fullStatus[93] = (int8_t)currentStatus.vvt1Angle;
fullStatus[94] = currentStatus.vvtTargetAngle; fullStatus[94] = currentStatus.vvt1TargetAngle;
fullStatus[95] = currentStatus.vvtDuty; fullStatus[95] = currentStatus.vvt1Duty;
fullStatus[96] = lowByte(currentStatus.flexBoostCorrection); fullStatus[96] = lowByte(currentStatus.flexBoostCorrection);
fullStatus[97] = highByte(currentStatus.flexBoostCorrection); fullStatus[97] = highByte(currentStatus.flexBoostCorrection);
fullStatus[98] = currentStatus.baroCorrection; fullStatus[98] = currentStatus.baroCorrection;
@ -653,6 +653,9 @@ void sendValues(uint16_t offset, uint16_t packetLength, byte cmd, byte portNum)
fullStatus[105] = currentStatus.oilPressure; fullStatus[105] = currentStatus.oilPressure;
fullStatus[106] = currentStatus.wmiPW; fullStatus[106] = currentStatus.wmiPW;
fullStatus[107] = currentStatus.wmiEmpty; fullStatus[107] = currentStatus.wmiEmpty;
fullStatus[108] = (int8_t)currentStatus.vvt2Angle;
fullStatus[109] = currentStatus.vvt2TargetAngle;
fullStatus[110] = currentStatus.vvt2Duty;
for(byte x=0; x<packetLength; x++) for(byte x=0; x<packetLength; x++)
{ {

View File

@ -13,7 +13,8 @@ Each decoder must have the following 4 functions (Where xxxx is the decoder name
* triggerPri_xxxx - Called each time the primary (No. 1) crank/cam signal is triggered (Called as an interrupt, so variables must be declared volatile) * triggerPri_xxxx - Called each time the primary (No. 1) crank/cam signal is triggered (Called as an interrupt, so variables must be declared volatile)
* triggerSec_xxxx - Called each time the secondary (No. 2) crank/cam signal is triggered (Called as an interrupt, so variables must be declared volatile) * triggerSec_xxxx - Called each time the secondary (No. 2) crank/cam signal is triggered (Called as an interrupt, so variables must be declared volatile)
* getRPM_xxxx - Returns the current RPM, as calculated by the decoder * getRPM_xxxx - Returns the current RPM, as calculated by the decoder
* getCrankAngle_xxxx - Returns the current crank angle, as calculated b the decoder * getCrankAngle_xxxx - Returns the current crank angle, as calculated by the decoder
* getCamAngle_xxxx - Returns the current CAM angle, as calculated by the decoder
And each decoder must utlise at least the following variables: And each decoder must utlise at least the following variables:
toothLastToothTime - The time (In uS) that the last primary tooth was 'seen' toothLastToothTime - The time (In uS) that the last primary tooth was 'seen'
@ -500,6 +501,18 @@ void triggerSec_missingTooth()
secondaryToothCount++; secondaryToothCount++;
} }
toothLastSecToothTime = curTime2; toothLastSecToothTime = curTime2;
//Record the VVT Angle
if( (revolutionOne == 1) )
{
int16_t curAngle;
curAngle = getCrankAngle();
while(curAngle > 360) { curAngle -= 360; }
curAngle -= configPage4.triggerAngle; //Value at TDC
if( configPage6.vvtMode == VVT_MODE_CLOSED_LOOP ) { curAngle -= configPage10.vvtCLMinAng; }
currentStatus.vvt1Angle = curAngle;
}
} //Trigger filter } //Trigger filter
} }
@ -2205,9 +2218,9 @@ int getCamAngle_Miata9905()
{ {
//lastVVTtime is the time between tooth #1 (10* BTDC) and the single cam tooth. //lastVVTtime is the time between tooth #1 (10* BTDC) and the single cam tooth.
//All cam angles in in BTDC, so the actual advance angle is 370 - fastTimeToAngle(lastVVTtime) - <the angle of the cam at 0 advance> //All cam angles in in BTDC, so the actual advance angle is 370 - fastTimeToAngle(lastVVTtime) - <the angle of the cam at 0 advance>
currentStatus.vvtAngle = 370 - fastTimeToAngle(lastVVTtime) - configPage10.vvtCLMinAng; currentStatus.vvt1Angle = 370 - fastTimeToAngle(lastVVTtime) - configPage10.vvtCLMinAng;
return currentStatus.vvtAngle; return currentStatus.vvt1Angle;
} }
void triggerSetEndTeeth_Miata9905() void triggerSetEndTeeth_Miata9905()

View File

@ -579,10 +579,10 @@ struct statuses {
bool knockActive; bool knockActive;
bool toothLogEnabled; bool toothLogEnabled;
bool compositeLogEnabled; bool compositeLogEnabled;
//int8_t vvtAngle; //int8_t vvt1Angle;
long vvtAngle; long vvt1Angle;
byte vvtTargetAngle; byte vvt1TargetAngle;
byte vvtDuty; byte vvt1Duty;
uint16_t injAngle; uint16_t injAngle;
byte ASEValue; byte ASEValue;
uint16_t vss; /**< Current speed reading. Natively stored in kph and converted to mph in TS if required */ uint16_t vss; /**< Current speed reading. Natively stored in kph and converted to mph in TS if required */
@ -592,6 +592,9 @@ struct statuses {
byte engineProtectStatus; byte engineProtectStatus;
byte wmiPW; byte wmiPW;
bool wmiEmpty; bool wmiEmpty;
long vvt2Angle;
byte vvt2TargetAngle;
byte vvt2Duty;
}; };
/** /**
@ -852,7 +855,7 @@ struct config6 {
byte egoCount; //The number of ignition cylces per step byte egoCount; //The number of ignition cylces per step
byte vvtMode : 2; //Valid VVT modes are 'on/off', 'open loop' and 'closed loop' byte vvtMode : 2; //Valid VVT modes are 'on/off', 'open loop' and 'closed loop'
byte vvtLoadSource : 2; //Load source for VVT (TPS or MAP) byte vvtLoadSource : 2; //Load source for VVT (TPS or MAP)
byte vvtCLDir : 1; //VVT direction (advance or retard) byte vvtPWMdir : 1; //VVT direction (normal or reverse)
byte vvtCLUseHold : 1; //Whether or not to use a hold duty cycle (Most cases are Yes) byte vvtCLUseHold : 1; //Whether or not to use a hold duty cycle (Most cases are Yes)
byte vvtCLAlterFuelTiming : 1; byte vvtCLAlterFuelTiming : 1;
byte boostCutEnabled : 1; byte boostCutEnabled : 1;
@ -862,7 +865,7 @@ struct config6 {
byte ego_sdelay; //Time in seconds after engine starts that closed loop becomes available byte ego_sdelay; //Time in seconds after engine starts that closed loop becomes available
byte egoRPM; //RPM must be above this for closed loop to function byte egoRPM; //RPM must be above this for closed loop to function
byte egoTPSMax; //TPS must be below this for closed loop to function byte egoTPSMax; //TPS must be below this for closed loop to function
byte vvtPin : 6; byte vvt1Pin : 6;
byte useExtBaro : 1; byte useExtBaro : 1;
byte boostMode : 1; //Simple of full boost control byte boostMode : 1; //Simple of full boost control
byte boostPin : 6; byte boostPin : 6;
@ -1117,8 +1120,8 @@ struct config10 {
byte vvtCLKP; //Byte 127 byte vvtCLKP; //Byte 127
byte vvtCLKI; //Byte 128 byte vvtCLKI; //Byte 128
byte vvtCLKD; //Byte 129 byte vvtCLKD; //Byte 129
uint16_t vvtCLMinAng; //Bytes 130-131 int16_t vvtCLMinAng; //Bytes 130-131
uint16_t vvtCLMaxAng; //Bytes 132-133 int16_t vvtCLMaxAng; //Bytes 132-133
byte crankingEnrichTaper; //Byte 134 byte crankingEnrichTaper; //Byte 134
@ -1163,8 +1166,13 @@ struct config10 {
byte wmiAdvBins[6]; //Bytes 159-164 byte wmiAdvBins[6]; //Bytes 159-164
byte wmiAdvAdj[6]; //Additional advance (in degrees) byte wmiAdvAdj[6]; //Additional advance (in degrees)
//Bytes 165-170 //Bytes 165-170
byte vvtCLminDuty;
byte vvtCLmaxDuty;
byte vvt2Pin : 6;
byte unused11_174_1 : 1;
byte unused11_174_2 : 1;
byte unused11_171_191[21]; //Bytes 171-191 byte unused11_175_191[18]; //Bytes 175-191
#if defined(CORE_AVR) #if defined(CORE_AVR)
}; };

View File

@ -1267,6 +1267,7 @@ void setPinMapping(byte boardID)
pinIdle2 = 53; //2 wire idle control pinIdle2 = 53; //2 wire idle control
pinBoost = 7; //Boost control pinBoost = 7; //Boost control
pinVVT_1 = 6; //Default VVT output pinVVT_1 = 6; //Default VVT output
pinVVT_2 = 48; //Default VVT2 output
pinFuelPump = 4; //Fuel pump output pinFuelPump = 4; //Fuel pump output
pinStepperDir = 16; //Direction pin for DRV8825 driver pinStepperDir = 16; //Direction pin for DRV8825 driver
pinStepperStep = 17; //Step pin for DRV8825 driver pinStepperStep = 17; //Step pin for DRV8825 driver
@ -1317,6 +1318,7 @@ void setPinMapping(byte boardID)
pinIdle2 = 6; //2 wire idle control pinIdle2 = 6; //2 wire idle control
pinBoost = 7; //Boost control pinBoost = 7; //Boost control
pinVVT_1 = 4; //Default VVT output pinVVT_1 = 4; //Default VVT output
pinVVT_2 = 48; //Default VVT2 output
pinFuelPump = 45; //Fuel pump output (Goes to ULN2803) pinFuelPump = 45; //Fuel pump output (Goes to ULN2803)
pinStepperDir = 16; //Direction pin for DRV8825 driver pinStepperDir = 16; //Direction pin for DRV8825 driver
pinStepperStep = 17; //Step pin for DRV8825 driver pinStepperStep = 17; //Step pin for DRV8825 driver
@ -1417,13 +1419,11 @@ void setPinMapping(byte boardID)
/* = PD0; */ //CANRX /* = PD0; */ //CANRX
/* = PD1; */ //CANTX /* = PD1; */ //CANTX
/* = PD2; */ //(DO NOT USE FOR SPEEDUINO) - SDIO_CMD /* = PD2; */ //(DO NOT USE FOR SPEEDUINO) - SDIO_CMD
/* = PD3; */ // pinVVT_2 = PD3; //
/* = PD4; */ //
pinFlex = PD4; pinFlex = PD4;
/* = PD5;*/ //TXD2 /* = PD5;*/ //TXD2
/* = PD6; */ //RXD2 /* = PD6; */ //RXD2
pinCoil1 = PD7; // pinCoil1 = PD7; //
/* = PD7; */ //
/* = PD8; */ // /* = PD8; */ //
pinCoil5 = PD9;// pinCoil5 = PD9;//
/* = PD10; */ // /* = PD10; */ //
@ -1512,6 +1512,7 @@ void setPinMapping(byte boardID)
pinIdle1 = 5; //Single wire idle control pinIdle1 = 5; //Single wire idle control
pinBoost = 4; pinBoost = 4;
pinVVT_1 = 11; //Default VVT output pinVVT_1 = 11; //Default VVT output
pinVVT_2 = 48; //Default VVT2 output
pinIdle2 = 4; //2 wire idle control (Note this is shared with boost!!!) pinIdle2 = 4; //2 wire idle control (Note this is shared with boost!!!)
pinFuelPump = 40; //Fuel pump output pinFuelPump = 40; //Fuel pump output
pinStepperDir = 16; //Direction pin for DRV8825 driver pinStepperDir = 16; //Direction pin for DRV8825 driver
@ -1780,6 +1781,7 @@ void setPinMapping(byte boardID)
pinIdle2 = 6; //ICV pin3 pinIdle2 = 6; //ICV pin3
pinBoost = 7; //Boost control pinBoost = 7; //Boost control
pinVVT_1 = 4; //VVT output pinVVT_1 = 4; //VVT output
pinVVT_2 = 48; //Default VVT2 output
pinFuelPump = 45; //Fuel pump output (Goes to ULN2003) pinFuelPump = 45; //Fuel pump output (Goes to ULN2003)
pinStepperDir = 16; //Stepper valve isn't used with these pinStepperDir = 16; //Stepper valve isn't used with these
pinStepperStep = 17; //Stepper valve isn't used with these pinStepperStep = 17; //Stepper valve isn't used with these
@ -1818,6 +1820,7 @@ void setPinMapping(byte boardID)
pinIdle2 = 47; //2 wire idle control - NOT USED pinIdle2 = 47; //2 wire idle control - NOT USED
pinBoost = 7; //Boost control pinBoost = 7; //Boost control
pinVVT_1 = 6; //Default VVT output pinVVT_1 = 6; //Default VVT output
pinVVT_2 = 48; //Default VVT2 output
pinFuelPump = 4; //Fuel pump output pinFuelPump = 4; //Fuel pump output
pinStepperDir = 25; //Direction pin for DRV8825 driver pinStepperDir = 25; //Direction pin for DRV8825 driver
pinStepperStep = 24; //Step pin for DRV8825 driver pinStepperStep = 24; //Step pin for DRV8825 driver
@ -1863,6 +1866,7 @@ void setPinMapping(byte boardID)
pinIdle2 = 10; //2 wire idle control pinIdle2 = 10; //2 wire idle control
pinFuelPump = 23; //Fuel pump output pinFuelPump = 23; //Fuel pump output
pinVVT_1 = 11; //Default VVT output pinVVT_1 = 11; //Default VVT output
pinVVT_2 = 48; //Default VVT2 output
pinStepperDir = 32; //Direction pin for DRV8825 driver pinStepperDir = 32; //Direction pin for DRV8825 driver
pinStepperStep = 31; //Step pin for DRV8825 driver pinStepperStep = 31; //Step pin for DRV8825 driver
pinStepperEnable = 30; //Enable pin for DRV8825 driver pinStepperEnable = 30; //Enable pin for DRV8825 driver
@ -1908,6 +1912,7 @@ void setPinMapping(byte boardID)
pinIdle2 = 43; //2 wire idle control pinIdle2 = 43; //2 wire idle control
pinFuelPump = 41; //Fuel pump output pinFuelPump = 41; //Fuel pump output
pinVVT_1 = 44; //Default VVT output pinVVT_1 = 44; //Default VVT output
pinVVT_2 = 48; //Default VVT2 output
pinStepperDir = 32; //Direction pin for DRV8825 driver pinStepperDir = 32; //Direction pin for DRV8825 driver
pinStepperStep = 31; //Step pin for DRV8825 driver pinStepperStep = 31; //Step pin for DRV8825 driver
pinStepperEnable = 30; //Enable pin for DRV8825 driver pinStepperEnable = 30; //Enable pin for DRV8825 driver
@ -2204,6 +2209,7 @@ void setPinMapping(byte boardID)
pinIdle2 = PA2; //2 wire idle control pinIdle2 = PA2; //2 wire idle control
pinBoost = PA1; //Boost control pinBoost = PA1; //Boost control
pinVVT_1 = PA0; //Default VVT output pinVVT_1 = PA0; //Default VVT output
pinVVT_2 = PA2; //Default VVT2 output
pinStepperDir = PC15; //Direction pin for DRV8825 driver pinStepperDir = PC15; //Direction pin for DRV8825 driver
pinStepperStep = PC14; //Step pin for DRV8825 driver pinStepperStep = PC14; //Step pin for DRV8825 driver
pinStepperEnable = PC13; //Enable pin for DRV8825 pinStepperEnable = PC13; //Enable pin for DRV8825
@ -2372,7 +2378,7 @@ void setPinMapping(byte boardID)
if ( (configPage4.fuelPumpPin != 0) && (configPage4.fuelPumpPin < BOARD_NR_GPIO_PINS) ) { pinFuelPump = pinTranslate(configPage4.fuelPumpPin); } if ( (configPage4.fuelPumpPin != 0) && (configPage4.fuelPumpPin < BOARD_NR_GPIO_PINS) ) { pinFuelPump = pinTranslate(configPage4.fuelPumpPin); }
if ( (configPage6.fanPin != 0) && (configPage6.fanPin < BOARD_NR_GPIO_PINS) ) { pinFan = pinTranslate(configPage6.fanPin); } if ( (configPage6.fanPin != 0) && (configPage6.fanPin < BOARD_NR_GPIO_PINS) ) { pinFan = pinTranslate(configPage6.fanPin); }
if ( (configPage6.boostPin != 0) && (configPage6.boostPin < BOARD_NR_GPIO_PINS) ) { pinBoost = pinTranslate(configPage6.boostPin); } if ( (configPage6.boostPin != 0) && (configPage6.boostPin < BOARD_NR_GPIO_PINS) ) { pinBoost = pinTranslate(configPage6.boostPin); }
if ( (configPage6.vvtPin != 0) && (configPage6.vvtPin < BOARD_NR_GPIO_PINS) ) { pinVVT_1 = pinTranslate(configPage6.vvtPin); } if ( (configPage6.vvt1Pin != 0) && (configPage6.vvt1Pin < BOARD_NR_GPIO_PINS) ) { pinVVT_1 = pinTranslate(configPage6.vvt1Pin); }
if ( (configPage6.useExtBaro != 0) && (configPage6.baroPin < BOARD_NR_GPIO_PINS) ) { pinBaro = configPage6.baroPin + A0; } if ( (configPage6.useExtBaro != 0) && (configPage6.baroPin < BOARD_NR_GPIO_PINS) ) { pinBaro = configPage6.baroPin + A0; }
if ( (configPage6.useEMAP != 0) && (configPage10.EMAPPin < BOARD_NR_GPIO_PINS) ) { pinEMAP = configPage10.EMAPPin + A0; } if ( (configPage6.useEMAP != 0) && (configPage10.EMAPPin < BOARD_NR_GPIO_PINS) ) { pinEMAP = configPage10.EMAPPin + A0; }
if ( (configPage10.fuel2InputPin != 0) && (configPage10.fuel2InputPin < BOARD_NR_GPIO_PINS) ) { pinFuel2Input = pinTranslate(configPage10.fuel2InputPin); } if ( (configPage10.fuel2InputPin != 0) && (configPage10.fuel2InputPin < BOARD_NR_GPIO_PINS) ) { pinFuel2Input = pinTranslate(configPage10.fuel2InputPin); }
@ -2383,6 +2389,7 @@ void setPinMapping(byte boardID)
if ( (configPage10.wmiEmptyPin != 0) && (configPage10.wmiEmptyPin < BOARD_NR_GPIO_PINS) ) { pinWMIEmpty = pinTranslate(configPage10.wmiEmptyPin); } if ( (configPage10.wmiEmptyPin != 0) && (configPage10.wmiEmptyPin < BOARD_NR_GPIO_PINS) ) { pinWMIEmpty = pinTranslate(configPage10.wmiEmptyPin); }
if ( (configPage10.wmiIndicatorPin != 0) && (configPage10.wmiIndicatorPin < BOARD_NR_GPIO_PINS) ) { pinWMIIndicator = pinTranslate(configPage10.wmiIndicatorPin); } if ( (configPage10.wmiIndicatorPin != 0) && (configPage10.wmiIndicatorPin < BOARD_NR_GPIO_PINS) ) { pinWMIIndicator = pinTranslate(configPage10.wmiIndicatorPin); }
if ( (configPage10.wmiEnabledPin != 0) && (configPage10.wmiEnabledPin < BOARD_NR_GPIO_PINS) ) { pinWMIEnabled = pinTranslate(configPage10.wmiEnabledPin); } if ( (configPage10.wmiEnabledPin != 0) && (configPage10.wmiEnabledPin < BOARD_NR_GPIO_PINS) ) { pinWMIEnabled = pinTranslate(configPage10.wmiEnabledPin); }
if ( (configPage10.vvt2Pin != 0) && (configPage10.vvt2Pin < BOARD_NR_GPIO_PINS) ) { pinVVT_2 = pinTranslate(configPage10.vvt2Pin); }
//Currently there's no default pin for Idle Up //Currently there's no default pin for Idle Up
pinIdleUp = pinTranslate(configPage2.idleUpPin); pinIdleUp = pinTranslate(configPage2.idleUpPin);
@ -2413,6 +2420,7 @@ void setPinMapping(byte boardID)
pinMode(pinStepperEnable, OUTPUT); pinMode(pinStepperEnable, OUTPUT);
pinMode(pinBoost, OUTPUT); pinMode(pinBoost, OUTPUT);
pinMode(pinVVT_1, OUTPUT); pinMode(pinVVT_1, OUTPUT);
pinMode(pinVVT_2, OUTPUT);
//This is a legacy mode option to revert the MAP reading behaviour to match what was in place prior to the 201905 firmware //This is a legacy mode option to revert the MAP reading behaviour to match what was in place prior to the 201905 firmware
if(configPage2.legacyMAP > 0) { digitalWrite(pinMAP, HIGH); } if(configPage2.legacyMAP > 0) { digitalWrite(pinMAP, HIGH); }
@ -2490,7 +2498,7 @@ void setPinMapping(byte boardID)
//And for inputs //And for inputs
#if defined(CORE_STM32) #if defined(CORE_STM32)
#ifndef ARDUINO_ARCH_STM32 //libmaple core aka STM32DUINO #ifdef INPUT_ANALOG
pinMode(pinMAP, INPUT_ANALOG); pinMode(pinMAP, INPUT_ANALOG);
pinMode(pinO2, INPUT_ANALOG); pinMode(pinO2, INPUT_ANALOG);
pinMode(pinO2_2, INPUT_ANALOG); pinMode(pinO2_2, INPUT_ANALOG);

View File

@ -9,8 +9,8 @@
#ifndef LOGGER_H #ifndef LOGGER_H
#define LOGGER_H #define LOGGER_H
#define LOG_ENTRY_SIZE 108 /**< The size of the live data packet. This MUST match ochBlockSize setting in the ini file */ #define LOG_ENTRY_SIZE 111 /**< The size of the live data packet. This MUST match ochBlockSize setting in the ini file */
#define SD_LOG_ENTRY_SIZE 108 /**< The size of the live data packet used by the SD car.*/ #define SD_LOG_ENTRY_SIZE 111 /**< The size of the live data packet used by the SD car.*/
void createLog(uint8_t *array); void createLog(uint8_t *array);
void createSDLog(uint8_t *array); void createSDLog(uint8_t *array);

View File

@ -114,10 +114,22 @@ void createLog(uint8_t *logBuffer)
logBuffer[90] = highByte(currentStatus.dwell); logBuffer[90] = highByte(currentStatus.dwell);
logBuffer[91] = currentStatus.CLIdleTarget; logBuffer[91] = currentStatus.CLIdleTarget;
logBuffer[92] = currentStatus.mapDOT; logBuffer[92] = currentStatus.mapDOT;
logBuffer[93] = (int8_t)currentStatus.vvtAngle; logBuffer[93] = (int8_t)currentStatus.vvt1Angle;
logBuffer[94] = currentStatus.vvtTargetAngle; logBuffer[94] = currentStatus.vvt1TargetAngle;
logBuffer[95] = currentStatus.vvtDuty; logBuffer[95] = currentStatus.vvt1Duty;
logBuffer[96] = lowByte(currentStatus.flexBoostCorrection); logBuffer[96] = lowByte(currentStatus.flexBoostCorrection);
logBuffer[97] = highByte(currentStatus.flexBoostCorrection); logBuffer[97] = highByte(currentStatus.flexBoostCorrection);
logBuffer[98] = currentStatus.baroCorrection; logBuffer[98] = currentStatus.baroCorrection;
logBuffer[99] = currentStatus.VE; //Current VE (%). Can be equal to VE1 or VE2 or a calculated value from both of them
logBuffer[100] = currentStatus.ASEValue; //Current ASE (%)
logBuffer[101] = lowByte(currentStatus.vss);
logBuffer[102] = highByte(currentStatus.vss);
logBuffer[103] = currentStatus.gear;
logBuffer[104] = currentStatus.fuelPressure;
logBuffer[105] = currentStatus.oilPressure;
logBuffer[106] = currentStatus.wmiPW;
logBuffer[107] = currentStatus.wmiEmpty;
logBuffer[108] = (int8_t)currentStatus.vvt2Angle;
logBuffer[109] = currentStatus.vvt2TargetAngle;
logBuffer[110] = currentStatus.vvt2Duty;
} }

View File

@ -183,7 +183,8 @@ void loop()
//This should only be run if the high speed logger are off because it will change the trigger interrupts back to defaults rather than the logger versions //This should only be run if the high speed logger are off because it will change the trigger interrupts back to defaults rather than the logger versions
if( (currentStatus.toothLogEnabled == false) && (currentStatus.compositeLogEnabled == false) ) { initialiseTriggers(); } if( (currentStatus.toothLogEnabled == false) && (currentStatus.compositeLogEnabled == false) ) { initialiseTriggers(); }
VVT_PIN_LOW(); VVT1_PIN_LOW();
VVT2_PIN_LOW();
DISABLE_VVT_TIMER(); DISABLE_VVT_TIMER();
boostDisable(); boostDisable();
if(configPage4.ignBypassEnabled > 0) { digitalWrite(pinIgnBypass, LOW); } //Reset the ignition bypass ready for next crank attempt if(configPage4.ignBypassEnabled > 0) { digitalWrite(pinIgnBypass, LOW); } //Reset the ignition bypass ready for next crank attempt
@ -242,6 +243,9 @@ void loop()
vvtControl(); vvtControl();
//Water methanol injection //Water methanol injection
wmiControl(); wmiControl();
//FOR TEST PURPOSES ONLY!!!
if(vvt2_pwm_value < vvt_pwm_max_count) vvt2_pwm_value++;
else vvt2_pwm_value = 1;
} }
if (BIT_CHECK(LOOP_TIMER, BIT_TIMER_4HZ)) if (BIT_CHECK(LOOP_TIMER, BIT_TIMER_4HZ))
{ {

View File

@ -294,6 +294,41 @@ bool integerPID::Compute(bool pOnE)
else return false; else return false;
} }
bool integerPID::ComputeVVT(uint32_t Sample)
{
if(!inAuto) return false;
/*Compute all the working error variables*/
long pTerm, iTerm, dTerm;
long input = *myInput;
long error = *mySetpoint - input;
long dInput = error - lastError;
long dTime = lastTime - Sample;
pTerm = kp * error;
if (ki != 0)
{
outputSum += (ki * error) * dTime; //integral += error × dt
if(outputSum > outMax*100) { outputSum = outMax*100; }
else if(outputSum < -outMax*100) { outputSum = -outMax*100; }
}
dTerm = dInput * kd * dTime;
/*Compute PID Output*/
long output = (pTerm + outputSum + dTerm) >> 5;
if(output > outMax) output = outMax;
else if(output < outMin) output = outMin;
*myOutput = output;
/*Remember some variables for next time*/
lastError = error;
lastTime = dTime;
return true;
}
bool integerPID::Compute2(int target, int input, bool pOnE) bool integerPID::Compute2(int target, int input, bool pOnE)
{ {
if(!inAuto) return false; if(!inAuto) return false;
@ -363,7 +398,7 @@ bool integerPID::Compute2(int target, int input, bool pOnE)
* it's called automatically from the constructor, but tunings can also * it's called automatically from the constructor, but tunings can also
* be adjusted on the fly during normal operation * be adjusted on the fly during normal operation
******************************************************************************/ ******************************************************************************/
void integerPID::SetTunings(byte Kp, byte Ki, byte Kd) void integerPID::SetTunings(byte Kp, byte Ki, byte Kd, byte realTime)
{ {
if ( dispKp == Kp && dispKi == Ki && dispKd == Kd ) return; //Only do anything if one of the values has changed if ( dispKp == Kp && dispKi == Ki && dispKd == Kd ) return; //Only do anything if one of the values has changed
dispKp = Kp; dispKi = Ki; dispKd = Kd; dispKp = Kp; dispKi = Ki; dispKd = Kd;
@ -374,13 +409,22 @@ void integerPID::SetTunings(byte Kp, byte Ki, byte Kd)
ki = Ki * SampleTimeInSec; ki = Ki * SampleTimeInSec;
kd = Kd / SampleTimeInSec; kd = Kd / SampleTimeInSec;
*/ */
long InverseSampleTimeInSec = 1000 / SampleTime; if(realTime == 0)
//New resolution, 2 shifts to improve ki here | kp 1.563% | ki 1.563% | kd 0.195% {
kp = (uint16_t)Kp<<2; long InverseSampleTimeInSec = 1000 / SampleTime;
ki = (long)(Ki<<2) / InverseSampleTimeInSec; //New resolution, 5 shifts to improve ki here | kp 3.125% | ki 3.125% | kd 0.781%
kd = (long)(Kd<<2) * InverseSampleTimeInSec; kp = (uint16_t)Kp<<5;
ki = (long)(Ki<<5) / InverseSampleTimeInSec;
kd = (long)(Kd<<5) * InverseSampleTimeInSec;
}
else
{
kp = Kp;
ki = Ki;
kd = Kd;
}
if(controllerDirection == REVERSE) if(controllerDirection == REVERSE)
{ {
kp = (0 - kp); kp = (0 - kp);
ki = (0 - ki); ki = (0 - ki);

View File

@ -88,7 +88,7 @@ class integerPID
#define MANUAL 0 #define MANUAL 0
#define DIRECT 0 #define DIRECT 0
#define REVERSE 1 #define REVERSE 1
#define PID_SHIFTS 7 //Increased resolution #define PID_SHIFTS 10 //Increased resolution
//commonly used functions ************************************************************************** //commonly used functions **************************************************************************
integerPID(long*, long*, long*, // * constructor. links the PID to the Input, Output, and integerPID(long*, long*, long*, // * constructor. links the PID to the Input, Output, and
@ -102,7 +102,8 @@ class integerPID
// calculation frequency can be set using SetMode // calculation frequency can be set using SetMode
// SetSampleTime respectively // SetSampleTime respectively
bool Compute2(int, int, bool); bool Compute2(int, int, bool);
bool ComputeVVT(uint32_t);
void SetOutputLimits(long, long); //clamps the output to a specific range. 0-255 by default, but void SetOutputLimits(long, long); //clamps the output to a specific range. 0-255 by default, but
//it's likely the user will want to change this depending on //it's likely the user will want to change this depending on
//the application //the application
@ -111,7 +112,7 @@ class integerPID
//available but not commonly used functions ******************************************************** //available but not commonly used functions ********************************************************
void SetTunings(byte, byte, // * While most users will set the tunings once in the void SetTunings(byte, byte, // * While most users will set the tunings once in the
byte); // constructor, this function gives the user the option byte, byte=0); // constructor, this function gives the user the option
// of changing tunings during runtime for Adaptive control // of changing tunings during runtime for Adaptive control
void SetControllerDirection(byte); // * Sets the Direction, or "Action" of the controller. DIRECT void SetControllerDirection(byte); // * Sets the Direction, or "Action" of the controller. DIRECT
// means the output will increase when error is positive. REVERSE // means the output will increase when error is positive. REVERSE