Merge pull request #124 from 0x15e/0x15e-master-amalgamation

Reset Control & Table-based Flex Fuel.
Removed usage of caches (Not required, can explain further if needed). The definitions of the caches etc need to be removed still
This commit is contained in:
Josh Stewart 2018-01-25 17:27:57 +11:00 committed by GitHub
commit 7a1b6f75cd
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
11 changed files with 548 additions and 77 deletions

2
.gitignore vendored
View File

@ -19,3 +19,5 @@ reference/hardware/v0.4/gerbers/Archive.zip
.vscode
.build
.kicad_pcb-bak
.vscode/c_cpp_properties.json
.vscode/launch.json

View File

@ -0,0 +1,251 @@
:1000000092C00000ABC00000A9C00000A7C0000063
:10001000A5C00000A3C00000A1C000009FC0000058
:100020009DC000009BC0000099C0000014C40000E7
:10003000B9C4000093C0000091C000008FC0000050
:100040008DC000008BC0000089C0000087C0000088
:1000500085C0000083C0000081C00000E7C100002F
:100060007DC000007BC0000079C0000077C00000A8
:1000700075C000002803530070006500650064002F
:10008000750069006E006F0020004D00650067007C
:1000900061002000320035003600300000003203DD
:1000A000410072006400750069006E006F0020005E
:1000B00028007700770077002E006100720064004E
:1000C000750069006E006F002E0063006300290058
:1000D00000000403090409023E00020100C03209C5
:1000E00004000001020201000524000110042402A2
:1000F000060524060001070582030800FF09040124
:1001000000020A0000000705040240000107058301
:10011000024000011201100102000008EB034B2015
:1001200001000102DC0111241FBECFEFD2E0DEBFCF
:10013000CDBF11E0A0E0B1E0ECE7FFE002C0059028
:100140000D92A831B107D9F722E0A8E1B1E001C0D2
:100150001D92A133B207E1F74CD00EC751CFFC017D
:10016000E058FF4FA081B1816C93A081B1819D01C6
:100170002F5F3F4F2E173F0761F0318320832FB74A
:10018000F894FC01EC57FF4F80818F5F80832FBF75
:10019000089512969C938E931197F1CF84B7877F21
:1001A00084BF0FB6F894A895809160008861809311
:1001B0006000109260000FBE87E690E09093CD0043
:1001C0008093CC0086E08093CA001092C80088E13A
:1001D0008093C900539A5A9A8AB180638AB98BB1C5
:1001E00080638BB92DD384E085BD5F9A579A279899
:1001F0000895D4DF2FB7F89480EA91E0909321021C
:100200008093200290932302809322022FBF2FB766
:10021000F8948BE191E090939C0180939B019093E3
:100220009E0180939D012FBF78948C0183E0F82E6E
:100230009FB7F894809124029FBF8038D1F080E06E
:1002400091E048D6EC0197FD14C0909116019923D6
:1002500051F0863441F460E680EA91E080DF61E0AD
:1002600080EA91E07CDF6C2F80EA91E078DF1092E9
:1002700016018FB7F894C0919F018FBFA89902C053
:10028000C13618F1A89A80919F01882319F05D98D2
:10029000F0921801C15008F042C0809118018823E3
:1002A00041F080911801815080931801811101C0A3
:1002B0005D9A80911901882341F080911901815044
:1002C00080931901811101C05C9A9FB7F8948091C5
:1002D00024029FBF8823F1F0E0912202F0912302D3
:1002E000919182E0E032F807C1F1F0932302E093AC
:1002F00022022FB7F8948091240281508093240227
:100300002FBF8091C80085FFFCCF9093CE005C98F2
:10031000F092190180E091E0CFD5C5D489CFE0916A
:100320009D01F0919E01619181E0EB39F80781F028
:10033000F0939E01E0939D019FB7F89480919F01F7
:10034000815080939F019FBF80E091E067D5A2CF4D
:1003500010939E0100939D01EFCF20EA31E030938E
:10036000230220932202C5CF80E091E013C580E0F4
:1003700091E0ABC40F931F93CF938C01FC01848950
:10038000C0E3813021F0C0E2823009F0C0E0F80122
:100390008389823009F4C860F80185898730E9F1E2
:1003A0008830E9F1863009F4C2601092C9001092D9
:1003B000C8001092CA00F801278530894189528906
:1003C0002115F1EE3F074105510559F1CA01B90167
:1003D000969587957795679560587B47814E9F4F97
:1003E000A3D5215031093093CD002093CC00C09388
:1003F000CA00F80187859089A189B2898115914E3B
:10040000A105B10589F082E08093C80088E9809356
:10041000C900CF911F910F910895C460C6CFC660E7
:10042000C4CF20E130E0DFCF80E0EECF1F920F920B
:100430000FB60F9211242F933F934F935F936F93B7
:100440007F938F939F93AF93BF93EF93FF936091AD
:10045000CE008EB3843019F48BE191E080DEFF9101
:10046000EF91BF91AF919F918F917F916F915F912C
:100470004F913F912F910F900FBE0F901F901895A5
:1004800023B1FC01858580FF07C027FD05C081E001
:10049000809316015F9808955F9A0895292F332756
:1004A0002230310571F02330310581F021303105E2
:1004B000A1F482E190E024E131E0FA01318320836C
:1004C00008958EE390E026ED30E0F7CF9927813054
:1004D000910571F038F0029771F090E080E030E023
:1004E00020E0EBCFE2EDF0E0849190E09F01E5CFDA
:1004F000EEE9F0E0F9CFE4E7F0E0F6CFAC0128E078
:1005000030E080E02417350718F08295807F089549
:100510008F5F220F331FF6CF8093E900EBEEF0E000
:10052000808181608083EDEEF0E010826093EC00CA
:1005300040838091EE00881F8827881F08951092BD
:10054000F40080E08093E9001092F0001092E8003F
:100550001092ED009091EB009E7F9093EB008F5FE7
:10056000853081F708958091290287FF11C080911D
:10057000E80082FF06C08091E8008B778093E80056
:1005800003C08EB38111F3CF08958EB38823E1F3B6
:100590008091E80080FFF9CF8091E8008E77EECF60
:1005A00085E69091EC0090FF06C09091E80090FFE6
:1005B00006C080E008959091E80092FDFACF9EB3C6
:1005C0009923A1F09EB3953099F09091EB0095FDA1
:1005D00011C09091E10092FFE4CF9091E1009B7FE8
:1005E0009093E1008150E9F684E0089582E0089557
:1005F00083E0089581E0089520912F023091300228
:1006000026173707A0F06115710529F42091E8003D
:100610002E772093E80030E06115710551F4311117
:1006200008C08091E80082FF30C080E00895B901E1
:10063000F2CF2091E80023FD30C02091E80022FD98
:10064000F0CF2EB3222359F12EB3253021F1209182
:10065000E80020FFE1CF2091F200FC01CF016115FD
:10066000710511F0283050F031E0283009F030E009
:100670002091E8002E772093E800CECF81918093DF
:10068000F100615071092F5FE9CF8EB3882339F0F3
:100690008EB3853031F683E0089581E0089582E0DD
:1006A000089520912F023091300226173707A0F0CD
:1006B0006115710529F42091E8002E772093E80058
:1006C00030E06115710551F4311108C08091E800E6
:1006D00082FF31C080E00895B901F2CF2091E80097
:1006E00023FD31C02091E80022FDF0CF2EB322235C
:1006F00061F12EB3253029F12091E80020FFE1CFF0
:100700002091F200FC01CF016115710511F0283034
:1007100050F031E0283009F030E02091E8002E77E9
:100720002093E800CECF84918093F100615071094D
:100730002F5F3196E8CF8EB3882339F08EB38530A2
:1007400029F683E0089581E0089582E00895611517
:10075000710529F42091E8002B772093E8006115BA
:10076000710531F48091E80080FF20C080E0089599
:100770002091E80023FD22C02EB3222309F12EB3DD
:100780002530D1F02091E80022FFE9CF2091F2003E
:10079000222301F39C012F5F3F4F4091F100FC01A8
:1007A000408361507109C90189F7D4CF8EB3882382
:1007B00039F08EB38530B1F683E0089581E0089575
:1007C00082E0089542D044D01EBA109227021092BF
:1007D00026021092250284E089BD89B5826089BD18
:1007E00009B400FEFDCF8091D800982F9F77909399
:1007F000D80080688093D800809163008E7F8093BA
:1008000063008091D8008F7D8093D8008091E000B4
:100810008E7F8093E0008091E1008E7F8093E100E5
:100820008091E20081608093E2008091E100877F07
:100830008093E1008091E20088608093E200089557
:10084000C1DF81E08093280208951092E2000895AC
:100850001092E10008951F920F920FB60F9211248B
:100860002F933F934F935F936F937F938F939F93B8
:10087000AF93BF93EF93FF938091E10080FF1BC084
:100880008091E20080FF17C08091E1008E7F80930D
:10089000E1008091E2008E7F8093E2008091E2008F
:1008A00080618093E2008091D80080628093D800BC
:1008B00019BC1EBAF7D18091E10084FF27C0809156
:1008C000E20084FF23C084E089BD89B5826089BDD0
:1008D00009B400FEFDCF8091D8008F7D8093D800B1
:1008E0008091E1008F7E8093E1008091E2008F7E15
:1008F0008093E2008091E20081608093E200809129
:10090000270281114DC081E08EBBCCD18091E100E6
:1009100083FF27C08091E20083FF23C08091E10024
:10092000877F8093E10082E08EBB10922702809146
:10093000E1008E7F8093E1008091E2008E7F8093C2
:10094000E2008091E20080618093E200F8DD42E005
:1009500060E080E0E1DD8091F00088608093F0004D
:10096000A1D18091E10082FF0AC08091E20082FF64
:1009700006C08091E1008B7F8093E10093D1FF91CD
:10098000EF91BF91AF919F918F917F916F915F9107
:100990004F913F912F910F900FBE0F901F90189580
:1009A00084E0B2CF1F920F920FB60F921124FF92E4
:1009B0000F931F932F933F934F935F936F937F9367
:1009C0008F939F93AF93BF93CF93DF93EF93FF9357
:1009D000C9EED0E088818770F82E188200EF10E011
:1009E000F8018081877F808378941DD0F8941882E5
:1009F000F801808188608083F882FF91EF91DF9118
:100A0000CF91BF91AF919F918F917F916F915F91A6
:100A10004F913F912F911F910F91FF900F900FBE1B
:100A20000F901F9018951F93CF93DF93CDB7DEB72C
:100A3000AA970FB6F894DEBF0FBECDBFE9E2F2E091
:100A40008091F100819322E0E133F207C9F78091B0
:100A5000290290912A029A3008F022C1E92FF0E091
:100A6000ED5CFA4F83C23D056205500662055006F3
:100A7000BD05D90550062B063706803881F082382F
:100A800009F00EC180912D0287708093E90080915A
:100A9000EB0085FB882780F91092E90006C0809161
:100AA000250290912602911182609091E800977F33
:100AB0009093E8008093F1001092F1008091E8009B
:100AC0008E772EC0282F2D7F09F0EAC08823D1F021
:100AD000823051F18091E80083FF0AC08091EB00E1
:100AE00080628093EB008091E800877F8093E8002C
:100AF000AA960FB6F894DEBF0FBECDBFDF91CF919F
:100B00001F91089580912B02813021F7933009F0D5
:100B100080E0809326021092E9008091E800877FB0
:100B20008093E80020DDD6CF80912B028111F3CF96
:100B300080912D02877071F28093E9002091EB0083
:100B400020FFC8CF933031F48091EB008062809316
:100B5000EB00E1CF9091EB0090619093EB0021E0EE
:100B600030E001C0220F8A95EAF72093EA00109244
:100B7000EA008091EB008860EACF811191C010916A
:100B80002B028091E800877F8093E800ECDC809165
:100B9000E80080FF0AC0812F8F7792E009F093E090
:100BA0009EBB80688093E30095CF8EB38111EFCF19
:100BB00091CF8058823008F073C080912B029091C1
:100BC0002C028C3D23E0920799F583E08A838AE228
:100BD00089834FB7F894DE01139620E03EE051E29E
:100BE000E32FF0E050935700E49120FF03C0E2951B
:100BF000EF703F5FEF7080E38E0F8A3310F087E372
:100C00008E0F90E08D939D932F5F243149F74FBF56
:100C10008091E800877F8093E8006AE270E0CE016F
:100C20000196EADC8091E8008B778093E80052CF50
:100C3000AE014F5F5F4F60912D0230DCBC01892B0C
:100C400009F448CF9091E800977F9093E80089815C
:100C50009A8127DDE7CF803819F58091E800877FFA
:100C60008093E800809127028093F10027CF8111C3
:100C700017C090912B02923008F02CCF8091E800A1
:100C8000877F8093E800909327026DDC8091270294
:100C9000811104C083E08EBB67DB1CCF84E0FBCFF7
:100CA00066DB18CF0895CF938EB3882359F0C09197
:100CB000E900C7701092E9008091E80083FDB3DE7F
:100CC000C093E900CF9108950895CF93DF93EC018D
:100CD0008091E80083FF0FC0288180912D029091C0
:100CE0002E022817190639F480912A028132C1F0A8
:100CF00028F4803249F1DF91CF9108958232C1F119
:100D00008332C9F7809129028132A9F78091E800E6
:100D1000877F8093E80060912B02CE01D5DF37C03A
:100D200080912902813A39F78091E800877F80938A
:100D3000E80067E070E0CE010F965EDC8091E8008D
:100D40008B778093E800D7CF80912902813299F682
:100D50008091E800877F8093E80067E070E0CE0133
:100D60000F96F5DCCE0106DB8091E8008E77E9CFA7
:100D700080912902813209F0BECF8091E800877FFF
:100D80008093E80080912B028D87CE0179DBDF9183
:100D9000CF91E9CB0F931F93CF93DF93EC01FC012D
:100DA0003D9689E0DF011D928A95E9F78A819B8152
:100DB0002C8110E0211114E00981A0DB812B482F48
:100DC000426061E8802FA8DB882311F18E819F812A
:100DD000288510E0211114E00D8190DB812B482F34
:100DE000426060E8802F98DB882391F08A859B859C
:100DF0002C8510E0211114E0C98580DB812B482F60
:100E0000426061EC8C2FDF91CF911F910F9184CBC9
:100E100080E0DF91CF911F910F910895CF93C62F5E
:100E20002EB32430F1F4FC01478550896189728921
:100E3000452B462B472BA9F081818093E9008091B7
:100E4000E80085FF05C0C093F10080E0CF910895D0
:100E50008091E8008E778093E800A2DB882399F3E5
:100E6000F5CF82E0F3CF2EB3243021F5FC01478586
:100E7000508961897289452B462B472BD9F0818196
:100E80008093E9008091F200811102C080E0089512
:100E90009091E8008091E8008E778093E80095FDBE
:100EA000F5CF7EDB811107C09091E8009E7790938B
:100EB000E800089582E008952EB3243051F4FC0137
:100EC0004785508961897289452B462B472B09F04C
:100ED000CACF08952EB3243019F08FEF9FEF0895F5
:100EE000FC014785508961897289452B462B472B28
:100EF000A1F385818093E9008091E80082FFEDCF26
:100F00008091F200882369F08091F10090E02091B7
:100F1000F200211105C02091E8002B772093E80012
:100F200008958FEF9FEFF3CFA1E21A2EAA1BBB1BF0
:100F3000FD010DC0AA1FBB1FEE1FFF1FA217B307A5
:100F4000E407F50720F0A21BB30BE40BF50B661FBB
:100F5000771F881F991F1A9469F76095709580957F
:100F600090959B01AC01BD01CF010895EE0FFF1FCD
:0C0F70000590F491E02D0994F894FFCF57
:100F7C0000034000000440000002080000000000D4
:080F8C0000000000000001005C
:00000001FF

View File

@ -1,4 +1,4 @@
;-------------------------------------------------------------------------------
;-------------------------------------------------------------------------------
#unset CAN_COMMANDS
#unset enablehardware_test
@ -10,7 +10,7 @@
versionInfo = "S" ;This info is what is displayed to user
[TunerStudio]
iniSpecVersion = 3.46
iniSpecVersion = 3.51
;-------------------------------------------------------------------------------
@ -158,8 +158,8 @@ page = 1
;Page 2 is all general settings (Previously part of page 1)
;--------------------------------------------------
page = 2
flexBoostLow = scalar, S08, 0, "kPa", 1.0, 0.0, -127, 127, 0
flexBoostHigh = scalar, U08, 1, "kPa", 1.0, 0.0, 0.0, 255, 0
unused2-1 = scalar, S08, 0, "kPa", 1.0, 0.0, -127, 127, 0
unused2-2 = scalar, U08, 1, "kPa", 1.0, 0.0, 0.0, 255, 0
asePct = scalar, U08, 2, "%", 1.0, 0.0, 0.0, 95.0, 0
aseCount = scalar, U08, 3, "s", 1.0, 0.0, 0.0, 255, 0
wueRates = array, U08, 4, [10], "%", 1.0, 0.0, 0.0, 255, 0
@ -236,10 +236,10 @@ page = 2
oddfire3 = scalar, U16, 53, "deg", 1.0, 0.0, 0.0, 720, 0 ; * ( 2 byte)
oddfire4 = scalar, U16, 55, "deg", 1.0, 0.0, 0.0, 720, 0 ; * ( 2 byte)
flexFuelLow = scalar, U08, 57, "%", 1.0, 0.0, 0.0, 250.0, 0
flexFuelHigh = scalar, U08, 58, "%", 1.0, 0.0, 0.0, 250.0, 0
flexAdvLow = scalar, U08, 59, "Deg", 1.0, 0.0, 0.0, 250.0, 0
flexAdvHigh = scalar, U08, 60, "Deg", 1.0, 0.0, 0.0, 250.0, 0
unused2-57 = scalar, U08, 57, "%", 1.0, 0.0, 0.0, 250.0, 0
unused2-58 = scalar, U08, 58, "%", 1.0, 0.0, 0.0, 250.0, 0
unused2-59 = scalar, U08, 59, "Deg", 1.0, 0.0, 0.0, 250.0, 0
unused2-60 = scalar, U08, 60, "Deg", 1.0, 0.0, 0.0, 250.0, 0
iacCLminDuty = scalar, U08, 61, "%", 1.0, 0.0, 0.0, 100.0, 0 ; Minimum and maximum duty cycles when using closed loop idle
iacCLmaxDuty = scalar, U08, 62, "%", 1.0, 0.0, 0.0, 100.0, 0
@ -281,8 +281,10 @@ page = 4
useResync = bits, U08, 6,[7:7], "No", "Yes"
sparkDur = scalar, U08, 7, "ms", 0.1, 0, 0, 25.5, 1 ; Spark duration
trigPatternSec = bits, U08, 8,[0:7], "Single tooth cam", "4-1 cam", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID"
unused4-9 = scalar, U08, 9, "ms", 0.1, 0.0, 0.0, 25.5, 1
unused4-10 = scalar, U08, 10, "ms", 0.1, 0.0, 0.0, 25.5, 1
bootloaderCaps = scalar, U08, 9, "level", 1, 0, 0, 255, 0
resetControl_custom = bits, U08, 10,[0:1], "Disabled", "Prevent When Running", "Prevent Always", "Serial Command"
resetControl_standard = bits, U08, 10,[0:1], "Disabled", "INVALID", "INVALID", "Enabled"
resetControlPin = bits, U08, 10,[2:7], "Board Default", "INVALID", "INVALID", "3", "4", "5", "6", "7", "8", "9", "10", "11", "12", "13", "14", "15", "16", "17", "18", "19", "20", "21", "22", "23", "24", "25", "26", "27", "28", "29", "30", "31", "32", "33", "34", "35", "36", "37", "38", "39", "40", "41", "42", "43", "44", "45", "46", "47", "48", "49", "50", "51", "52", "53", "54", "A8", "A9", "A10", "A11", "A12", "A13", "A14", "A15", "INVALID"
SkipCycles = scalar, U08, 11, "cycles", 1, 0, 0, 255, 0
; name = array, type, offset, shape, units, scale, translate, lo, hi, digits
@ -717,8 +719,16 @@ page = 10
stagedInjSizePri = scalar, U16, 28, "cc/min", 1, 0, 0, 1500, 0
stagedInjSizeSec = scalar, U16, 30, "cc/min", 1, 0, 0, 1500, 0
lnchCtrlTPS = scalar, U08, 32, "%TPS", 1, 0, 0, 100, 0
unused11_32_192 = array, U08, 33, [158], "RPM", 100.0, 0.0, 100, 25500, 0
flexBoostBins = array, U08, 33, [6], "%", 1.0, 0.0, 0.0, 250.0, 0
; The boost range is obviously arbitrary since int16_t has ~32k in both directions
flexBoostAdj = array, S16, 39, [6], "kPa", 1.0, 0.0, -500.0, 500.0, 0
flexFuelBins = array, U08, 51, [6], "%", 1.0, 0.0, 0.0, 250.0, 0
flexFuelAdj = array, U08, 57, [6], "%", 1.0, 0.0, 0.0, 250.0, 0
flexAdvBins = array, U08, 63, [6], "%", 1.0, 0.0, 0.0, 250.0, 0
flexAdvAdj = array, U08, 69, [6], "Deg", 1.0, 0.0, 0.0, 250.0, 0
unused11_75_192 = array, U08, 75,[117],"RPM", 100.0, 0.0, 100, 25500, 0
;-------------------------------------------------------------------------------
@ -755,6 +765,9 @@ page = 10
requiresPowerCycle = stagedInjSizePri
requiresPowerCycle = stagedInjSizeSec
requiresPowerCycle = stagingEnabled
requiresPowerCycle = resetControl_custom
requiresPowerCycle = resetControl_standard
requiresPowerCycle = resetControlPin
defaultValue = pinLayout, 1
defaultValue = TrigPattern, 0
@ -805,6 +818,9 @@ page = 10
defaultValue = VVTasOnOff, 0
defaultValue = stagingEnabled, 0
defaultValue = lnchCtrlTPS, 0
defaultValue = resetControl_custom, 0
defaultValue = resetControl_standard, 0
defaultValue = bootloaderCaps, 0
; defaultValue = obd_address, 0
;Default pins
@ -815,6 +831,10 @@ page = 10
defaultValue = fuelPumpPin, 0
defaultValue = tachoPin, 0
defaultValue = perToothIgn, 0
defaultValue = resetControlPin, 0
controllerPriority = bootloaderCaps
[Menu]
;----------------------------------------------------------------------------
@ -849,6 +869,7 @@ menuDialog = main
subMenu = triggerSettings, "Trigger Setup"
;subMenu = OLED, "OLED Setup"
subMenu = airdensity_curve, "IAT Density"
subMenu = reset_control, "Reset Control"
menu = "&Tuning"
@ -991,15 +1012,12 @@ menuDialog = main
includeAFR = "When enabled, the current AFR reading is incorporated directly in the pulsewidth calculation as a percentage of the current target ratio. VE table must be retuned when this value is changed. "
useExtBaro = "By Default, Speeduino will measure barometric pressure upon startup. Optionally however, a 2nd pressure sensor can be used to perform live barometric readings whilst the system is on."
flexEnabled = "Turns on readings from the Flex sensor and enables the below adjustments"
flexFreqLow = "The frequency of the sensor at 0% ethanol (50Hz for standard GM/Continental sensor)"
flexEnabled = "Turns on readings from the Flex sensor and enables the below adjustments"
flexFreqLow = "The frequency of the sensor at 0% ethanol (50Hz for standard GM/Continental sensor)"
flexFreqHigh = "The frequency of the sensor at 100% ethanol (150Hz for standard GM/Continental sensor)"
flexFuelLow = "Fuel % to be used for the lowest ethanol reading (Typically 100%. ie No adjustment)"
flexFuelHigh = "Fuel % to be used for the highest ethanol reading (Typically 163% for 100% ethanol)"
flexAdvLow = "Additional advance (in degrees) at lowest ethanol reading (Typically 0)"
flexAdvHigh = "Additional advance (in degrees) at highest ethanol reading (Typically 10-20 degrees)"
flexBoostHigh = "This amount that will be added to the boost target at E100. Between E0 and E100, the amount added to the boost target will be scaled from 0 to this value"
flexBoostLow = "Typically should be set to 0, but can be used to lower boost at E0 if the bast tune is setup with some ethanol"
flexFuelAdj = "Fuel % to be used for the current ethanol % (Typically 100% @ 0%, 163% @ 100%)"
flexAdvAdj = "Additional advance (in degrees) for the current ethanol % (Typically 0 @ 0%, 10-20 @ 100%)"
flexBoostAdj = "Adjustment, in kPa, to the boost target for the current ethanol %. Negative values are allowed to lower boost at lower ethanol % if necessary."
flatSArm = "The RPM switch point that determines whether an eganged clutch is for launch control or flat shift. Below this figure, an engaged clutch is considered to be for launch, above this figure an active clutch input will be considered a flat shift. This should be set at least several hundred RPM above idle"
flatSSoftWin= "The number of RPM below the flat shift point where the softlimit will be applied (aka Soft limit window). Recommended values are 200-1000"
@ -1097,6 +1115,10 @@ menuDialog = main
stagedInjSizePri= "Size of the primary injectors. The sum of the Pri and Sec injectors values MUST match the value used in the req_fuel calculation"
stagedInjSizeSec= "Size of the secondary injectors. The sum of the Pri and Sec injectors values MUST match the value used in the req_fuel calculation"
resetControl_standard = "Whether to enable reset control of the Arduino's automatic reset feature. If this feature is enabled, the selected control pin will be held high at all times. In order to update your Speeduino's firmware, you will first need to open a serial terminal and send a 'U' command so that the Arduino resets when the upload starts. The control pin should be connected to the Arduino's reset pin."
resetControl_custom = "How to control the Arduino's automatic reset feature. NOTE: Some of these settings require modifying your hardware and replacing the Arduino bootloader. See the Wiki for more details.\n\nDisabled: Allow the Arduino to reset when a new serial connection is made.\n\nPrevent When Running: Hold the control pin high while the engine is running.\n\nPrevent Always: Always hold the control pin high.\n\nSerial Command: Normally hold the control pin high, but pull it low when the 'U' serial command is issued and reset upon receiving more data."
resetControlPin = "The Arduino pin used to control resets."
[UserDefined]
; Enhanced TunerStudio dialogs can be defined here
@ -1142,42 +1164,23 @@ menuDialog = main
panel = engine_constants_east, East
# Flex fuel stuff
dialog = flexFueling, "Flex Fuel"
field = "Flex sensor", flexEnabled
dialog = flexFuelSettings, "", yAxis
field = "Flex Fuel Sensor ", flexEnabled
field = "Low (E0) ", flexFreqLow, { flexEnabled }
field = "High (E100) ", flexFreqHigh, { flexEnabled }
dialog = flexLeft, ""
field = "Component"
field = "Sensor Frequency"
field = "Fuel Adjustment"
field = "Additional advance"
field = "Additional boost", { boostEnabled }
dialog = flexFuelWest, "", border
panel = flexFuelSettings, North
dialog = flexMiddle, ""
field = "Low (E0)"
field = "", flexFreqLow, { flexEnabled }
field = "", flexFuelLow, { flexEnabled }
field = "", flexAdvLow, { flexEnabled }
field = "", flexBoostLow, { boostEnabled }
dialog = flexCurves, "", indexCard
panel = flex_fuel_curve, { flexEnabled }
panel = flex_adv_curve, { flexEnabled }
panel = flex_boost_curve, { flexEnabled && boostEnabled }
dialog = flexRight, ""
field = "High (E100)"
field = "", flexFreqHigh, { flexEnabled }
field = "", flexFuelHigh, { flexEnabled }
field = "", flexAdvHigh, { flexEnabled }
field = "", flexBoostHigh, { flexEnabled && boostEnabled }
dialog = flexMain, "Flex Fuel Calibration", xAxis
panel = flexLeft
panel = flexMiddle
panel = flexRight
dialog = flexFuelTop, ""
field = "Flex Fuel Sensor", flexEnabled
dialog = flexFueling, "Fuel Sensor Settings", yAxis
dialog = flexFueling, "Fuel Sensor Settings", border
topicHelp = "http://speeduino.com/wiki/index.php/Flex_Fuel"
panel = flexFuelTop
panel = flexMain
panel = flexFuelWest, West
panel = flexCurves, Center
dialog = tacho, "Tacho"
field = "Output pin", tachoPin
@ -1804,6 +1807,13 @@ menuDialog = main
topicHelp = "http://speeduino.com/wiki/index.php/Serial3_IO_interface"
field = "Enable Second Serial", enable_canbus
dialog = reset_control, "Reset Control"
; Control type options for custom firmware
field = "Control Type", resetControl_custom, { bootloaderCaps > 0 }, { bootloaderCaps > 0 }
; Control type options for standard / unmodifyable firmware
field = "Control Type", resetControl_standard, { bootloaderCaps == 0 }, { bootloaderCaps == 0 }
field = "Control Pin", resetControlPin
;-------------------------------------------------------------------------------
; General help text
@ -1985,6 +1995,30 @@ cmdtestspk450dc = "E\x03\x0C"
; xBins = wueAFRBins, coolant
; yBins = wueAFRRates
; Flex fuel correction curves
curve = flex_fuel_curve, "Flex Fuel Adjustments"
columnLabel = "Ethanol", "Fuel"
xAxis = 0, 100, 5
yAxis = 0, 255, 10
xBins = flexFuelBins, flex
yBins = flexFuelAdj
size = 400, 200
curve = flex_adv_curve, "Flex Timing Advance"
columnLabel = "Ethanol", "Advance"
xAxis = 0, 100, 5
yAxis = 0, 100, 5
xBins = flexAdvBins, flex
yBins = flexAdvAdj
size = 400, 200
curve = flex_boost_curve, "Flex Boost Adjustments"
columnLabel = "Ethanol", "Boost"
xAxis = 0, 100, 5
yAxis = -100, 200, 5
xBins = flexBoostBins, flex
yBins = flexBoostAdj
size = 400, 200
[TableEditor]
; table_id, map3d_id, "title", page
@ -2237,6 +2271,8 @@ cmdtestspk450dc = "E\x03\x0C"
indicator = { hardLimitOn }, "Hard Limit OFF","Hard Limiter", white, black, red, black
indicator = { boostCutOut }, "Ign Cut OFF", "Ign Cut (Boost)", white, black, red, black
indicator = { sync }, "No Sync", "Sync", white, black, green, black
indicator = { resetLockOn }, "Reset Lock OFF","Reset Lock ON", red, black, green, black
indicator = { bootloaderCaps > 0 }, "Std. Boot", "Custom Boot", white, black, white, black
;-------------------------------------------------------------------------------
@ -2247,7 +2283,7 @@ cmdtestspk450dc = "E\x03\x0C"
; you change it.
ochGetCommand = "r\$tsCanId\x30%2o%2c"
ochBlockSize = 81
ochBlockSize = 84
secl = scalar, U08, 0, "sec", 1.000, 0.000
status1 = scalar, U08, 1, "bits", 1.000, 0.000
@ -2334,7 +2370,10 @@ cmdtestspk450dc = "E\x03\x0C"
pulseWidth2 = scalar, U16, 75, "ms", 0.001, 0.000
pulseWidth3 = scalar, U16, 77, "ms", 0.001, 0.000
pulseWidth4 = scalar, U16, 79, "ms", 0.001, 0.000
status3 = scalar, U08, 81, "bits", 1.000, 0.000
resetLockOn = bits, U08, 81, [0:0]
unused81_1-7 = bits, U08, 81, [1:7]
flexBoostCor = scalar, S16, 81, "kPa", 1.000, 0.000
#if CELSIUS
coolant = { coolantRaw - 40 } ; Temperature readings are offset by 40 to allow for negatives
iat = { iatRaw - 40 } ; Temperature readings are offset by 40 to allow for negatives

View File

@ -80,9 +80,11 @@ void boostControl()
//If flex fuel is enabled, there can be an adder to the boost target based on ethanol content
if( configPage2.flexEnabled == 1 )
{
int16_t boostAdder = (((int16_t)configPage2.flexBoostHigh - (int16_t)configPage2.flexBoostLow) * currentStatus.ethanolPct) / 100;
boostAdder = boostAdder + configPage2.flexBoostLow; //Required in case flexBoostLow is less than 0
currentStatus.boostTarget += boostAdder;
currentStatus.boostTarget += table2D_getValue(&flexBoostTable, currentStatus.ethanolPct);;
}
else
{
currentStatus.flexBoostCorrection = 0;
}
if(currentStatus.boostTarget > 0)
@ -120,7 +122,10 @@ void boostControl()
boostDisable();
}
}
else { DISABLE_BOOST_TIMER(); } // Disable timer channel
else { // Disable timer channel and zero the flex boost correction status
DISABLE_BOOST_TIMER();
currentStatus.flexBoostCorrection = 0;
}
boostCounter++;
}

View File

@ -12,7 +12,7 @@
#define canbusPage 9//Config Page 9
#define warmupPage 10 //Config Page 10
#define SERIAL_PACKET_SIZE 81
#define SERIAL_PACKET_SIZE 84
byte currentPage = 1;//Not the same as the speeduino config page numbers
bool isMap = true;

View File

@ -183,6 +183,24 @@ void command()
break;
case 'U': //User wants to reset the Arduino (probably for FW update)
if (resetControl != RESET_CONTROL_DISABLED)
{
#ifndef SMALL_FLASH_MODE
if (!cmdPending) { Serial.println(F("Comms halted. Next byte will reset the Arduino.")); }
#endif
while (Serial.available() == 0) { }
digitalWrite(pinResetControl, LOW);
}
else
{
#ifndef SMALL_FLASH_MODE
if (!cmdPending) { Serial.println(F("Reset control is currently disabled.")); }
#endif
}
break;
case 'V': // send VE table and constants in binary
sendPage(false);
break;
@ -293,6 +311,16 @@ void command()
sendToothLog(true); //Sends tooth log values as chars
break;
case '`': //Custom 16u2 firmware is making its presence known
cmdPending = true;
if (Serial.available() >= 1) {
configPage2.bootloaderCaps = Serial.read();
cmdPending = false;
}
break;
case '?':
#ifndef SMALL_FLASH_MODE
Serial.println
@ -320,6 +348,7 @@ void command()
"Z - Display calibration values\n"
"T - Displays 256 tooth log entries in binary\n"
"r - Displays 256 tooth log entries\n"
"U - Prepare for firmware update. The next byte received will cause the Arduino to reset.\n"
"? - Displays this help page"
));
#endif
@ -457,6 +486,10 @@ void sendValues(uint16_t offset, uint16_t packetLength, byte cmd, byte portNum)
fullStatus[79] = lowByte(currentStatus.PW4); //Pulsewidth 4 multiplied by 10 in ms. Have to convert from uS to mS.
fullStatus[80] = highByte(currentStatus.PW4); //Pulsewidth 4 multiplied by 10 in ms. Have to convert from uS to mS.
fullStatus[81] = currentStatus.status3;
fullStatus[82] = lowByte(currentStatus.flexBoostCorrection);
fullStatus[83] = highByte(currentStatus.flexBoostCorrection);
for(byte x=0; x<packetLength; x++)
{
if (portNum == 0) { Serial.write(fullStatus[offset+x]); }

View File

@ -280,10 +280,10 @@ static inline bool correctionDFCO()
static inline byte correctionFlex()
{
byte flexValue = 100;
if(configPage2.flexEnabled == 1)
if (configPage2.flexEnabled == 1)
{
byte flexRange = configPage2.flexFuelHigh - configPage2.flexFuelLow;
flexValue = percentage(currentStatus.ethanolPct, flexRange) + 100;
flexValue = table2D_getValue(&flexFuelTable, currentStatus.ethanolPct);
}
return flexValue;
}
@ -406,11 +406,7 @@ static inline int8_t correctionFlexTiming(int8_t advance)
byte ignFlexValue = advance;
if( configPage2.flexEnabled == 1 ) //Check for flex being enabled
{
byte flexRange = configPage2.flexAdvHigh - configPage2.flexAdvLow;
if (currentStatus.ethanolPct != 0) { currentStatus.flexIgnCorrection = percentage(currentStatus.ethanolPct, flexRange); }
else { currentStatus.flexIgnCorrection = 0; }
currentStatus.flexIgnCorrection = table2D_getValue(&flexAdvTable, currentStatus.ethanolPct);
ignFlexValue = advance + currentStatus.flexIgnCorrection;
}
return ignFlexValue;

View File

@ -102,6 +102,14 @@
#define BIT_TIMER_15HZ 3
#define BIT_TIMER_30HZ 4
#define BIT_STATUS3_RESET_PREVENT 0 //Indicates whether reset prevention is enabled
#define BIT_STATUS3_UNUSED2 1
#define BIT_STATUS3_UNUSED3 2
#define BIT_STATUS3_UNUSED4 3
#define BIT_STATUS3_UNUSED5 4
#define BIT_STATUS3_UNUSED6 5
#define BIT_STATUS3_UNUSED7 6
#define VALID_MAP_MAX 1022 //The largest ADC value that is valid for the MAP sensor
#define VALID_MAP_MIN 2 //The smallest ADC value that is valid for the MAP sensor
@ -144,6 +152,11 @@
#define STAGING_MODE_TABLE 0
#define STAGING_MODE_AUTO 1
#define RESET_CONTROL_DISABLED 0
#define RESET_CONTROL_PREVENT_WHEN_RUNNING 1
#define RESET_CONTROL_PREVENT_ALWAYS 2
#define RESET_CONTROL_SERIAL_COMMAND 3
#define MAX_RPM 18000 //This is the maximum rpm that the ECU will attempt to run at. It is NOT related to the rev limiter, but is instead dictates how fast certain operations will be allowed to run. Lower number gives better performance
#define engineSquirtsPerCycle 2 //Would be 1 for a 2 stroke
@ -184,6 +197,9 @@ struct table2D injectorVCorrectionTable; //6 bin injector voltage correction (2D
struct table2D IATDensityCorrectionTable; //9 bin inlet air temperature density correction (2D)
struct table2D IATRetardTable; //6 bin ignition adjustment based on inlet air temperature (2D)
struct table2D rotarySplitTable; //8 bin ignition split curve for rotary leading/trailing (2D)
struct table2D flexFuelTable; //6 bin flex fuel correction table for fuel adjustments (2D)
struct table2D flexAdvTable; //6 bin flex fuel correction table for timing advance (2D)
struct table2D flexBoostTable; //6 bin flex fuel correction table for boost adjustments (2D)
//These are for the direct port manipulation of the injectors and coils
volatile byte *inj1_pin_port;
@ -236,6 +252,9 @@ int ignition4EndAngle = 0;
//This is used across multiple files
unsigned long revolutionTime; //The time in uS that one revolution would take at current speed (The time tooth 1 was last seen, minus the time it was seen prior to that)
//This needs to be here because using the config page directly can prevent burning the setting
byte resetControl = RESET_CONTROL_DISABLED;
volatile byte TIMER_mask;
volatile byte LOOP_TIMER;
@ -313,6 +332,8 @@ struct statuses {
uint16_t canin[16]; //16bit raw value of selected canin data for channel 0-15
uint8_t current_caninchannel = 0; //start off at channel 0
uint16_t crankRPM = 400; //The actual cranking RPM limit. Saves us multiplying it everytime from the config page
volatile byte status3;
int16_t flexBoostCorrection; //Amount of boost added based on flex
//Helpful bitwise operations:
//Useful reference: http://playground.arduino.cc/Code/BitMath
@ -327,8 +348,8 @@ struct statuses currentStatus; //The global status object
//This mostly covers off variables that are required for fuel
struct config2 {
int8_t flexBoostLow; //Must be signed to allow for negatives
byte flexBoostHigh;
byte unused2_1;
byte unused2_2;
byte asePct; //Afterstart enrichment (%)
byte aseCount; //Afterstart enrichment cycles. This is the number of ignition cycles that the afterstart enrichment % lasts for
byte wueValues[10]; //Warm up enrichment array (10 bytes)
@ -403,10 +424,10 @@ struct config2 {
uint16_t oddfire2; //The ATDC angle of channel 2 for oddfire
uint16_t oddfire3; //The ATDC angle of channel 3 for oddfire
uint16_t oddfire4; //The ATDC angle of channel 4 for oddfire
byte flexFuelLow; //Fuel % to be used for the lowest ethanol reading (Typically 100%)
byte flexFuelHigh; //Fuel % to be used for the highest ethanol reading (Typically 163%)
byte flexAdvLow; //Additional advance (in degrees) at lowest ethanol reading (Typically 0)
byte flexAdvHigh; //Additional advance (in degrees) at highest ethanol reading (Varies, usually 10-20)
byte unused2_57;
byte unused2_58;
byte unused2_59;
byte unused2_60;
byte iacCLminDuty;
byte iacCLmaxDuty;
@ -443,8 +464,11 @@ struct config4 {
byte sparkDur; //Spark duration in ms * 10
byte trigPatternSec; //Mode for Missing tooth secondary trigger. Either single tooth cam wheel or 4-1
byte unused4_9;
byte unused4_10;
uint8_t bootloaderCaps; //Capabilities of the bootloader over stock. e.g., 0=Stock, 1=Reset protection, etc.
byte resetControl : 2; //Which method of reset control to use (0=None, 1=Prevent When Running, 2=Prevent Always, 3=Serial Command)
byte resetControlPin : 6;
byte StgCycles; //The number of initial cycles before the ignition should fire when first cranking
byte dwellCont : 1; //Fixed duty dwell control
@ -653,7 +677,16 @@ struct config10 {
uint16_t stagedInjSizePri;
uint16_t stagedInjSizeSec;
byte lnchCtrlTPS;
byte unused11_28_192[159];
uint8_t flexBoostBins[6];
int16_t flexBoostAdj[6]; //kPa to be added to the boost target @ current ethanol (negative values allowed)
uint8_t flexFuelBins[6];
uint8_t flexFuelAdj[6]; //Fuel % @ current ethanol (typically 100% @ 0%, 163% @ 100%)
uint8_t flexAdvBins[6];
uint8_t flexAdvAdj[6]; //Additional advance (in degrees) @ current ethanol (typically 0 @ 0%, 10-20 @ 100%)
//And another three corn rows die.
byte unused11_75_192[117];
#if defined(CORE_AVR)
};
@ -661,6 +694,16 @@ struct config10 {
} __attribute__((__packed__)); //The 32 bit systems require all structs to be fully packed
#endif
struct flexCachedLookups
{
bool fuelReady;
bool advanceReady;
bool boostReady;
byte fuel;
byte advance;
int16_t boost;
};
struct flexCachedLookups flexLookupCache = { false, false, false, 0, 0, 0 };
byte pinInjector1; //Output pin injector 1
byte pinInjector2; //Output pin injector 2
@ -720,6 +763,7 @@ byte pinLaunch;
byte pinIgnBypass; //The pin used for an ignition bypass (Optional)
byte pinFlex; //Pin with the flex sensor attached
byte pinBaro; //Pin that an external barometric pressure sensor is attached to (If used)
byte pinResetControl; // Output pin used control resetting the Arduino
// global variables // from speeduino.ino
extern struct statuses currentStatus; // from speeduino.ino

View File

@ -161,6 +161,10 @@ void setup()
loadConfig();
doUpdates(); //Check if any data items need updating (Occurs ith firmware updates)
//Always start with a clean slate on the bootloader capabilities level
//This should be 0 until we hear otherwise from the 16u2
configPage2.bootloaderCaps = 0;
Serial.begin(115200);
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) //ATmega2561 does not have Serial3
if (configPage9.enable_canbus == 1) { CANSerial.begin(115200); }
@ -218,6 +222,19 @@ void setup()
rotarySplitTable.values = configPage10.rotarySplitValues;
rotarySplitTable.axisX = configPage10.rotarySplitBins;
flexFuelTable.valueSize = SIZE_BYTE;
flexFuelTable.xSize = 6;
flexFuelTable.values = configPage11.flexFuelAdj;
flexFuelTable.axisX = configPage11.flexFuelBins;
flexAdvTable.valueSize = SIZE_BYTE;
flexAdvTable.xSize = 6;
flexAdvTable.values = configPage11.flexAdvAdj;
flexAdvTable.axisX = configPage11.flexAdvBins;
flexBoostTable.valueSize = SIZE_INT;
flexBoostTable.xSize = 6;
flexBoostTable.values16 = configPage11.flexBoostAdj;
flexBoostTable.axisX = configPage11.flexBoostBins;
//Setup the calibration tables
loadCalibration();
@ -691,6 +708,7 @@ void setup()
setFuelSchedule2(100, (unsigned long)(configPage2.primePulse * 100));
setFuelSchedule3(100, (unsigned long)(configPage2.primePulse * 100));
setFuelSchedule4(100, (unsigned long)(configPage2.primePulse * 100));
initialisationComplete = true;
digitalWrite(LED_BUILTIN, HIGH);
}
@ -1658,7 +1676,17 @@ void loop()
}
}
} //Ignition schedules on
if (!BIT_CHECK(currentStatus.status3, BIT_STATUS3_RESET_PREVENT) && resetControl == RESET_CONTROL_PREVENT_WHEN_RUNNING) {
//Reset prevention is supposed to be on while the engine is running but isn't. Fix that.
digitalWrite(pinResetControl, HIGH);
BIT_SET(currentStatus.status3, BIT_STATUS3_RESET_PREVENT);
}
} //Has sync and RPM
else if (BIT_CHECK(currentStatus.status3, BIT_STATUS3_RESET_PREVENT) && resetControl == RESET_CONTROL_PREVENT_WHEN_RUNNING) {
digitalWrite(pinResetControl, LOW);
BIT_CLEAR(currentStatus.status3, BIT_STATUS3_RESET_PREVENT);
}
} //loop()
/*

View File

@ -8,7 +8,7 @@
void doUpdates()
{
#define CURRENT_DATA_VERSION 7
#define CURRENT_DATA_VERSION 8
//May 2017 firmware introduced a -40 offset on the ignition table. Update that table to +40
if(EEPROM.read(EEPROM_DATA_VERSION) == 2)
@ -92,6 +92,32 @@ void doUpdates()
loadConfig(); //Reload the config after changing everything in EEPROM
}
if (EEPROM.read(EEPROM_DATA_VERSION) == 7) {
//Convert whatever flex fuel settings are there into the new tables
configPage11.flexBoostAdj[0] = (int8_t)configPage1.unused2_1;
configPage11.flexFuelAdj[0] = configPage1.unused2_57;
configPage11.flexAdvAdj[0] = configPage1.unused2_59;
for (uint8_t x = 1; x < 6; x++)
{
uint8_t pct = x * 20;
configPage11.flexBoostBins[x] = configPage11.flexFuelBins[x] = configPage11.flexAdvBins[x] = pct;
int16_t boostAdder = (((configPage1.unused2_2 - (int8_t)configPage1.unused2_1) * pct) / 100) + (int8_t)configPage1.unused2_1;
configPage11.flexBoostAdj[x] = boostAdder;
uint8_t fuelAdder = (((configPage1.unused2_58 - configPage1.unused2_57) * pct) / 100) + configPage1.unused2_57;
configPage11.flexFuelAdj[x] = fuelAdder;
uint8_t advanceAdder = (((configPage1.unused2_60 - configPage1.unused2_59) * pct) / 100) + configPage1.unused2_59;
configPage11.flexAdvAdj[x] = advanceAdder;
}
writeAllConfig();
EEPROM.write(EEPROM_DATA_VERSION, 8);
}
//Final check is always for 255 and 0 (Brand new arduino)
if( (EEPROM.read(EEPROM_DATA_VERSION) == 0) || (EEPROM.read(EEPROM_DATA_VERSION) == 255) )
{

View File

@ -48,6 +48,32 @@ byte pinTranslate(byte rawPin)
return outputPin;
}
void setResetControlPinState()
{
BIT_CLEAR(currentStatus.status3, BIT_STATUS3_RESET_PREVENT);
/* Setup reset control initial state */
switch (resetControl)
{
case RESET_CONTROL_PREVENT_WHEN_RUNNING:
/* Set the reset control pin LOW and change it to HIGH later when we get sync. */
digitalWrite(pinResetControl, LOW);
BIT_CLEAR(currentStatus.status3, BIT_STATUS3_RESET_PREVENT);
break;
case RESET_CONTROL_PREVENT_ALWAYS:
/* Set the reset control pin HIGH and never touch it again. */
digitalWrite(pinResetControl, HIGH);
BIT_SET(currentStatus.status3, BIT_STATUS3_RESET_PREVENT);
break;
case RESET_CONTROL_SERIAL_COMMAND:
/* Set the reset control pin HIGH. There currently isn't any practical difference
between this and PREVENT_ALWAYS but it doesn't hurt anything to have them separate. */
digitalWrite(pinResetControl, HIGH);
BIT_CLEAR(currentStatus.status3, BIT_STATUS3_RESET_PREVENT);
break;
}
}
void setPinMapping(byte boardID)
{
switch (boardID)
@ -80,6 +106,7 @@ void setPinMapping(byte boardID)
pinFuelPump = 4; //Fuel pump output
pinTachOut = 49; //Tacho output pin
pinFlex = 19; // Flex sensor (Must be external interrupt enabled)
pinResetControl = 43; //Reset control output
#endif
break;
case 1:
@ -112,6 +139,7 @@ void setPinMapping(byte boardID)
pinFan = 47; //Pin for the fan output
pinFuelPump = 4; //Fuel pump output
pinFlex = 2; // Flex sensor (Must be external interrupt enabled)
pinResetControl = 43; //Reset control output
break;
#endif
case 2:
@ -148,6 +176,7 @@ void setPinMapping(byte boardID)
pinFan = A13; //Pin for the fan output
pinLaunch = 51; //Can be overwritten below
pinFlex = 2; // Flex sensor (Must be external interrupt enabled)
pinResetControl = 50; //Reset control output
#if defined(CORE_TEENSY)
pinTrigger = 23;
@ -196,6 +225,7 @@ void setPinMapping(byte boardID)
pinFan = 47; //Pin for the fan output (Goes to ULN2803)
pinLaunch = 51; //Can be overwritten below
pinFlex = 2; // Flex sensor (Must be external interrupt enabled)
pinResetControl = 43; //Reset control output
#if defined(CORE_TEENSY)
pinTrigger = 23;
@ -305,6 +335,7 @@ void setPinMapping(byte boardID)
pinFan = 35; //Pin for the fan output
pinLaunch = 12; //Can be overwritten below
pinFlex = 3; // Flex sensor (Must be external interrupt enabled)
pinResetControl = 44; //Reset control output
#if defined(CORE_TEENSY)
pinTrigger = 23;
@ -354,6 +385,8 @@ void setPinMapping(byte boardID)
pinFan = 47; //Pin for the fan output
pinTachOut = 49; //Tacho output pin
pinFlex = 2; // Flex sensor (Must be external interrupt enabled)
pinResetControl = 26; //Reset control output
#endif
break;
@ -389,6 +422,7 @@ void setPinMapping(byte boardID)
pinFan = 47; //Pin for the fan output
pinFuelPump = 4; //Fuel pump output
pinTachOut = 49; //Tacho output pin
pinResetControl = 26; //Reset control output
#endif
break;
@ -471,6 +505,7 @@ void setPinMapping(byte boardID)
pinSpareLOut1 = 32; //low current output spare1 - ONLY WITH DB
pinSpareLOut2 = 34; //low current output spare2 - ONLY WITH DB
pinSpareLOut3 = 36; //low current output spare3 - ONLY WITH DB
pinResetControl = 26; //Reset control output
break;
default:
@ -503,6 +538,7 @@ void setPinMapping(byte boardID)
pinFlex = 3; // Flex sensor (Must be external interrupt enabled)
pinBoost = 5;
pinIdle1 = 6;
pinResetControl = 43; //Reset control output
#endif
break;
}
@ -518,6 +554,17 @@ void setPinMapping(byte boardID)
if ( (configPage6.vvtPin != 0) && (configPage6.vvtPin < BOARD_NR_GPIO_PINS) ) { pinVVT_1 = pinTranslate(configPage6.vvtPin); }
if ( (configPage6.useExtBaro != 0) && (configPage6.baroPin < BOARD_NR_GPIO_PINS) ) { pinBaro = configPage6.baroPin + A0; }
/* Reset control is a special case. If reset control is enabled, it needs its initial state set BEFORE its pinMode.
If that doesn't happen and reset control is in "Serial Command" mode, the Arduino will end up in a reset loop
because the control pin will go low as soon as the pinMode is set to OUTPUT. */
if ( (configPage2.resetControl != 0) && (configPage2.resetControlPin < BOARD_NR_GPIO_PINS) )
{
resetControl = configPage2.resetControl;
pinResetControl = pinTranslate(configPage2.resetControlPin);
setResetControlPinState();
pinMode(pinResetControl, OUTPUT);
}
//Finally, set the relevant pin modes for outputs
pinMode(pinCoil1, OUTPUT);
pinMode(pinCoil2, OUTPUT);