Merge pull request #60 from noisymime/master

update for 03072018 release
This commit is contained in:
Autohome2 2018-07-03 21:51:12 +01:00 committed by GitHub
commit fbfa727f6f
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
12 changed files with 177 additions and 82 deletions

View File

@ -1,7 +1,7 @@
<?xml version="1.0" encoding="ISO-8859-1"?> <?xml version="1.0" encoding="ISO-8859-1"?>
<msq xmlns="http://www.msefi.com/:msq"> <msq xmlns="http://www.msefi.com/:msq">
<bibliography author="TunerStudio MS(Beta) 3.0.60.09 - EFI Analytics, Inc." tuneComment="" writeDate="Thu Jun 07 14:35:52 AEST 2018"/> <bibliography author="TunerStudio MS(Beta) 3.0.60.15 - EFI Analytics, Inc." tuneComment="" writeDate="Tue Jul 03 22:21:15 AEST 2018"/>
<versionInfo fileFormat="5.0" firmwareInfo="Speeduino+2018.5" nPages="10" signature="speeduino 201805"/> <versionInfo fileFormat="5.0" firmwareInfo="Speeduino+2018.6" nPages="10" signature="speeduino 201806"/>
<page> <page>
<pcVariable name="tsCanId">"CAN ID 0"</pcVariable> <pcVariable name="tsCanId">"CAN ID 0"</pcVariable>
<pcVariable cols="1" digits="0" name="algorithmLimits" rows="8"> <pcVariable cols="1" digits="0" name="algorithmLimits" rows="8">
@ -124,7 +124,7 @@
<constant name="injType">"Port"</constant> <constant name="injType">"Port"</constant>
<constant name="nCylinders">"4"</constant> <constant name="nCylinders">"4"</constant>
<constant name="algorithm">"MAP"</constant> <constant name="algorithm">"MAP"</constant>
<constant name="unused2_37d">"Off"</constant> <constant name="fixAngEnable">"Off"</constant>
<constant name="nInjectors">"4"</constant> <constant name="nInjectors">"4"</constant>
<constant name="engineType">"Even fire"</constant> <constant name="engineType">"Even fire"</constant>
<constant name="flexEnabled">"Off"</constant> <constant name="flexEnabled">"Off"</constant>
@ -151,8 +151,8 @@
<constant name="idleUpPolarity">"Inverted"</constant> <constant name="idleUpPolarity">"Inverted"</constant>
<constant name="idleUpEnabled">"Off"</constant> <constant name="idleUpEnabled">"Off"</constant>
<constant digits="0" name="idleUpAdder" units="% / Steps">163.0</constant> <constant digits="0" name="idleUpAdder" units="% / Steps">163.0</constant>
<constant digits="0" name="unused2-59" units="Deg">255.0</constant> <constant digits="0" name="taeTaperMin" units="RPM">1000.0</constant>
<constant digits="0" name="unused2-60" units="Deg">255.0</constant> <constant digits="0" name="taeTaperMax" units="RPM">4500.0</constant>
<constant digits="0" name="iacCLminDuty" units="%">0.0</constant> <constant digits="0" name="iacCLminDuty" units="%">0.0</constant>
<constant digits="0" name="iacCLmaxDuty" units="%">0.0</constant> <constant digits="0" name="iacCLmaxDuty" units="%">0.0</constant>
<constant digits="0" name="boostMinDuty" units="%">20.0</constant> <constant digits="0" name="boostMinDuty" units="%">20.0</constant>
@ -280,7 +280,7 @@
</constant> </constant>
</page> </page>
<page number="3" size="128"> <page number="3" size="128">
<constant digits="0" name="TrigAng" units="Deg">0.0</constant> <constant digits="0" name="TrigAng" units="Deg">10.0</constant>
<constant digits="0" name="FixAng" units="Deg">0.0</constant> <constant digits="0" name="FixAng" units="Deg">0.0</constant>
<constant digits="0" name="CrankAng" units="Deg">5.0</constant> <constant digits="0" name="CrankAng" units="Deg">5.0</constant>
<constant digits="0" name="TrigAngMul">0.0</constant> <constant digits="0" name="TrigAngMul">0.0</constant>
@ -873,7 +873,21 @@
<constant name="caninput_sel13">"Off"</constant> <constant name="caninput_sel13">"Off"</constant>
<constant name="caninput_sel14">"Off"</constant> <constant name="caninput_sel14">"Off"</constant>
<constant name="caninput_sel15">"Off"</constant> <constant name="caninput_sel15">"Off"</constant>
<constant name="caninput_source_can_address0">"0x100"</constant>
<constant name="caninput_source_can_address1">"0x100"</constant>
<constant name="caninput_source_can_address2">"0x100"</constant>
<constant name="caninput_source_can_address3">"0x100"</constant>
<constant name="caninput_source_can_address4">"0x100"</constant>
<constant name="caninput_source_can_address5">"0x100"</constant>
<constant name="caninput_source_can_address6">"0x100"</constant>
<constant name="caninput_source_can_address7">"0x100"</constant>
<constant name="caninput_source_can_address8">"0x706"</constant> <constant name="caninput_source_can_address8">"0x706"</constant>
<constant name="caninput_source_can_address9">"0x100"</constant>
<constant name="caninput_source_can_address10">"0x100"</constant>
<constant name="caninput_source_can_address11">"0x100"</constant>
<constant name="caninput_source_can_address12">"0x100"</constant>
<constant name="caninput_source_can_address13">"0x100"</constant>
<constant name="caninput_source_can_address14">"0x100"</constant>
<constant name="caninput_source_can_address15">"0x6FD"</constant> <constant name="caninput_source_can_address15">"0x6FD"</constant>
<constant name="caninput_source_start_byte0">"7"</constant> <constant name="caninput_source_start_byte0">"7"</constant>
<constant name="caninput_source_start_byte1">"7"</constant> <constant name="caninput_source_start_byte1">"7"</constant>
@ -964,7 +978,7 @@
<constant digits="0" name="unused10_124">255.0</constant> <constant digits="0" name="unused10_124">255.0</constant>
<constant digits="0" name="unused10_125">255.0</constant> <constant digits="0" name="unused10_125">255.0</constant>
<constant digits="0" name="unused10_126">255.0</constant> <constant digits="0" name="unused10_126">255.0</constant>
<constant digits="0" name="unused10_127">100.0</constant> <constant digits="0" name="unused10_127">124.0</constant>
</page> </page>
<page number="9" size="192"> <page number="9" size="192">
<constant cols="1" digits="0" name="crankingEnrichBins" rows="4" units="C"> <constant cols="1" digits="0" name="crankingEnrichBins" rows="4" units="C">
@ -1056,24 +1070,28 @@
9.0 9.0
10.0 10.0
</constant> </constant>
<constant cols="1" digits="0" name="unused11_75_191" rows="116" units="RPM"> <constant name="n2o_enable">"2 stage"</constant>
25500.0 <constant name="n2o_arming_pin">"34"</constant>
25500.0 <constant digits="0" name="n2o_minCLT" units="C">20.0</constant>
25500.0 <constant digits="0" name="n2o_maxMAP" units="kPa">250.0</constant>
25500.0 <constant digits="0" name="n2o_minTPS" units="%TPS">30.0</constant>
25500.0 <constant digits="1" name="n2o_maxAFR" units="kPa">18.0</constant>
25500.0 <constant name="n2o_stage1_pin">"30"</constant>
25500.0 <constant name="n2o_pin_polarity">"LOW"</constant>
25500.0 <constant name="n2o_unused">0</constant>
25500.0 <constant digits="0" name="n2o_stage1_minRPM" units="RPM">3000.0</constant>
25500.0 <constant digits="0" name="n2o_stage1_maxRPM" units="RPM">6000.0</constant>
25500.0 <constant digits="1" name="n2o_stage1_adderMin" units="ms">6.0</constant>
25500.0 <constant digits="1" name="n2o_stage1_adderMax" units="ms">3.0</constant>
25500.0 <constant digits="0" name="n2o_stage1_retard" units="Deg">5.0</constant>
25500.0 <constant name="n2o_stage2_pin">"31"</constant>
25500.0 <constant name="n2o_stage2_unused">0</constant>
25500.0 <constant digits="0" name="n2o_stage2_minRPM" units="RPM">6000.0</constant>
25500.0 <constant digits="0" name="n2o_stage2_maxRPM" units="RPM">7000.0</constant>
<constant digits="1" name="n2o_stage2_adderMin" units="ms">3.0</constant>
<constant digits="1" name="n2o_stage2_adderMax" units="ms">1.5</constant>
<constant digits="0" name="n2o_stage2_retard" units="Deg">5.0</constant>
<constant cols="1" digits="0" name="unused11_75_191" rows="99" units="RPM">
25500.0 25500.0
25500.0 25500.0
25500.0 25500.0
@ -1175,7 +1193,7 @@
25500.0 25500.0
</constant> </constant>
<constant digits="0" name="UNALLOCATED_TOP_9" units="RAW"> <constant digits="0" name="UNALLOCATED_TOP_9" units="RAW">
0.0 100.0
</constant> </constant>
</page> </page>
<settings Comment="These setting are only used if this msq is opened without a project."> <settings Comment="These setting are only used if this msq is opened without a project.">

Binary file not shown.

View File

@ -6,7 +6,7 @@
MTversion = 2.25 MTversion = 2.25
queryCommand = "Q" queryCommand = "Q"
signature = "speeduino 201806-dev" signature = "speeduino 201806"
versionInfo = "S" ;This info is what is displayed to user versionInfo = "S" ;This info is what is displayed to user
[TunerStudio] [TunerStudio]
@ -55,6 +55,7 @@
algorithmUnits = bits, U08, [0:2], "kPa", "% TPS", "%", "% TPS", "INVALID", "INVALID", "INVALID", "INVALID" algorithmUnits = bits, U08, [0:2], "kPa", "% TPS", "%", "% TPS", "INVALID", "INVALID", "INVALID", "INVALID"
algorithmLimits= array, U16, [8], "", 1.0, 0, 0, 511, 0, noMsqSave algorithmLimits= array, U16, [8], "", 1.0, 0, 0, 511, 0, noMsqSave
#define all_IO_Pins = "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" #define all_IO_Pins = "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"
#define IO_Pins_no_def = "INVALID", "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"
boostTableLabels = bits, U08, [0:1], "Duty Cycle %", "kPa" boostTableLabels = bits, U08, [0:1], "Duty Cycle %", "kPa"
@ -828,7 +829,7 @@ page = 10
flexAdvAdj = array, U08, 69, [6], "Deg", 1.0, 0.0, 0.0, 250.0, 0 flexAdvAdj = array, U08, 69, [6], "Deg", 1.0, 0.0, 0.0, 250.0, 0
n2o_enable = bits , U08, 75, [0:1], "Off","1 Stage","2 stage", "INVALID" n2o_enable = bits , U08, 75, [0:1], "Off","1 Stage","2 stage", "INVALID"
n2o_arming_pin = bits , U08, 75, [2:7], $all_IO_Pins n2o_arming_pin = bits , U08, 75, [2:7], $IO_Pins_no_def
#if CELSIUS #if CELSIUS
n2o_minCLT = scalar, U08, 76, "C", 1.0, -40, -40, 215, 0 n2o_minCLT = scalar, U08, 76, "C", 1.0, -40, -40, 215, 0
#else #else
@ -839,7 +840,7 @@ page = 10
n2o_maxAFR = scalar, U08, 79, "kPa", 0.1, 0.0, 0.0, 25.5, 1 n2o_maxAFR = scalar, U08, 79, "kPa", 0.1, 0.0, 0.0, 25.5, 1
n2o_stage1_pin = bits , U08, 80, [0:5], $all_IO_Pins n2o_stage1_pin = bits , U08, 80, [0:5], $IO_Pins_no_def
n2o_pin_polarity = bits , U08, 80, [6:6], "HIGH", "LOW" n2o_pin_polarity = bits , U08, 80, [6:6], "HIGH", "LOW"
n2o_unused = bits , U08, 80, [7:7], "INVALID", "INVALID" n2o_unused = bits , U08, 80, [7:7], "INVALID", "INVALID"
n2o_stage1_minRPM = scalar, U08, 81, "RPM", 100, 0.0, 1000, 10000, 0 n2o_stage1_minRPM = scalar, U08, 81, "RPM", 100, 0.0, 1000, 10000, 0
@ -848,7 +849,7 @@ page = 10
n2o_stage1_adderMax = scalar, U08, 84, "ms", 0.1, 0, 0, 25.5, 1 n2o_stage1_adderMax = scalar, U08, 84, "ms", 0.1, 0, 0, 25.5, 1
n2o_stage1_retard = scalar, U08, 85, "Deg", 1.0, 0.0, 0.0, 250.0, 0 n2o_stage1_retard = scalar, U08, 85, "Deg", 1.0, 0.0, 0.0, 250.0, 0
n2o_stage2_pin = bits , U08, 86, [0:5], $all_IO_Pins n2o_stage2_pin = bits , U08, 86, [0:5], $IO_Pins_no_def
n2o_stage2_unused = bits , U08, 86, [6:7], "INVALID", "INVALID", "INVALID", "INVALID" n2o_stage2_unused = bits , U08, 86, [6:7], "INVALID", "INVALID", "INVALID", "INVALID"
n2o_stage2_minRPM = scalar, U08, 87, "RPM", 100, 0.0, 1000, 10000, 0 n2o_stage2_minRPM = scalar, U08, 87, "RPM", 100, 0.0, 1000, 10000, 0
n2o_stage2_maxRPM = scalar, U08, 88, "RPM", 100, 0.0, 1000, 10000, 0 n2o_stage2_maxRPM = scalar, U08, 88, "RPM", 100, 0.0, 1000, 10000, 0
@ -899,6 +900,7 @@ page = 10
requiresPowerCycle = resetControlPin requiresPowerCycle = resetControlPin
requiresPowerCycle = n2o_enable requiresPowerCycle = n2o_enable
requiresPowerCycle = n2o_arming_pin requiresPowerCycle = n2o_arming_pin
requiresPowerCycle = n2o_pin_polarity
defaultValue = pinLayout, 1 defaultValue = pinLayout, 1
defaultValue = TrigPattern, 0 defaultValue = TrigPattern, 0
@ -950,6 +952,8 @@ page = 10
defaultValue = lnchCtrlTPS, 0 defaultValue = lnchCtrlTPS, 0
defaultValue = resetControl, 0 defaultValue = resetControl, 0
defaultValue = bootloaderCaps, 0 defaultValue = bootloaderCaps, 0
defaultValue = taeTaperMin, 1000
defaultValue = taeTaperMax, 5000
; defaultValue = obd_address, 0 ; defaultValue = obd_address, 0
;Default pins ;Default pins
@ -1173,6 +1177,7 @@ menuDialog = main
flexBoostAdj = "Adjustment, in kPa, to the boost target for the current ethanol %. Negative values are allowed to lower boost at lower ethanol % if necessary." flexBoostAdj = "Adjustment, in kPa, to the boost target for the current ethanol %. Negative values are allowed to lower boost at lower ethanol % if necessary."
n2o_arming_pin = "Pin that the nitrous arming/enagement switch is on." n2o_arming_pin = "Pin that the nitrous arming/enagement switch is on."
n2o_pin_polarity = "Whether Nitrous is active (Armed) when the pin is LOW or HIGH. If LOW is selected, the internal pullup will be used."
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" 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" 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"
@ -1623,6 +1628,7 @@ menuDialog = main
field = "Minimum CLT", n2o_minCLT, { n2o_enable > 0 } field = "Minimum CLT", n2o_minCLT, { n2o_enable > 0 }
field = "Minimum TPS", n2o_minTPS, { n2o_enable > 0 } field = "Minimum TPS", n2o_minTPS, { n2o_enable > 0 }
field = "Maximum MAP", n2o_maxMAP, { n2o_enable > 0 } field = "Maximum MAP", n2o_maxMAP, { n2o_enable > 0 }
field = "Leanest AFR", n2o_maxAFR, { n2o_enable > 0 }
dialog = NitrousControl, "Nitrous" dialog = NitrousControl, "Nitrous"
panel = NitrousMain, North panel = NitrousMain, North

View File

@ -62,7 +62,11 @@ void nitrousControl();
#define VVT_PIN_HIGH() *vvt_pin_port |= (vvt_pin_mask) #define VVT_PIN_HIGH() *vvt_pin_port |= (vvt_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_HIGH() *n2o_stage1_pin_port |= (n2o_stage1_pin_mask)
#define N2O_STAGE2_PIN_LOW() *n2o_stage2_pin_port &= ~(n2o_stage2_pin_mask)
#define N2O_STAGE2_PIN_HIGH() *n2o_stage2_pin_port |= (n2o_stage2_pin_mask)
#define READ_N2O_ARM_PIN() ((*n2o_arming_pin_port & n2o_arming_pin_mask) ? true : false)
volatile byte *boost_pin_port; volatile byte *boost_pin_port;
volatile byte boost_pin_mask; volatile byte boost_pin_mask;
@ -70,6 +74,12 @@ volatile byte *vvt_pin_port;
volatile byte vvt_pin_mask; volatile byte vvt_pin_mask;
volatile byte *fan_pin_port; volatile byte *fan_pin_port;
volatile byte fan_pin_mask; volatile byte fan_pin_mask;
volatile byte *n2o_stage1_pin_port;
volatile byte n2o_stage1_pin_mask;
volatile byte *n2o_stage2_pin_port;
volatile byte n2o_stage2_pin_mask;
volatile byte *n2o_arming_pin_port;
volatile byte n2o_arming_pin_mask;
volatile bool boost_pwm_state; volatile bool boost_pwm_state;
unsigned int boost_pwm_max_count; //Used for variable PWM frequency unsigned int boost_pwm_max_count; //Used for variable PWM frequency

View File

@ -75,6 +75,15 @@ void initialiseAuxPWM()
boost_pin_mask = digitalPinToBitMask(pinBoost); boost_pin_mask = digitalPinToBitMask(pinBoost);
vvt_pin_port = portOutputRegister(digitalPinToPort(pinVVT_1)); vvt_pin_port = portOutputRegister(digitalPinToPort(pinVVT_1));
vvt_pin_mask = digitalPinToBitMask(pinVVT_1); vvt_pin_mask = digitalPinToBitMask(pinVVT_1);
n2o_stage1_pin_port = portOutputRegister(digitalPinToPort(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_mask = digitalPinToBitMask(configPage10.n2o_stage2_pin);
n2o_arming_pin_port = portInputRegister(digitalPinToPort(configPage10.n2o_arming_pin));
n2o_arming_pin_mask = digitalPinToBitMask(configPage10.n2o_arming_pin);
if(configPage10.n2o_pin_polarity == 1) { pinMode(configPage10.n2o_arming_pin, INPUT_PULLUP); }
else { pinMode(configPage10.n2o_arming_pin, INPUT); }
#if defined(CORE_STM32) || defined(CORE_TEENSY) //2uS resolution Min 8Hz, Max 5KHz #if defined(CORE_STM32) || defined(CORE_TEENSY) //2uS resolution Min 8Hz, Max 5KHz
boost_pwm_max_count = 1000000L / (2 * configPage6.boostFreq * 2); //Converts the frequency in Hz to the number of ticks (at 2uS) it takes to complete 1 cycle. The x2 is there because the frequency is stored at half value (in a byte) to allow freqneucies up to 511Hz boost_pwm_max_count = 1000000L / (2 * configPage6.boostFreq * 2); //Converts the frequency in Hz to the number of ticks (at 2uS) it takes to complete 1 cycle. The x2 is there because the frequency is stored at half value (in a byte) to allow freqneucies up to 511Hz
@ -98,6 +107,9 @@ void initialiseAuxPWM()
if(vvt_pwm_max_count > 0) { Timer1.attachInterrupt(3, vvtInterrupt);} if(vvt_pwm_max_count > 0) { Timer1.attachInterrupt(3, vvtInterrupt);}
Timer1.resume(); Timer1.resume();
#endif #endif
currentStatus.nitrous_status = NITROUS_OFF;
} }
#define BOOST_HYSTER 40 #define BOOST_HYSTER 40
@ -209,41 +221,47 @@ void vvtControl()
void nitrousControl() void nitrousControl()
{ {
bool nitrousOn = false; //This tracks whether the control gets turned on at any point.
if(configPage10.n2o_enable > 0) if(configPage10.n2o_enable > 0)
{ {
bool isArmed = digitalRead(configPage10.n2o_arming_pin); bool isArmed = READ_N2O_ARM_PIN();
if (configPage10.n2o_pin_polarity == 1) { isArmed = !isArmed; } //If nirtrous is active when pin is low, flip the reading (n2o_pin_polarity = 0 = active when High) if (configPage10.n2o_pin_polarity == 1) { isArmed = !isArmed; } //If nitrous is active when pin is low, flip the reading (n2o_pin_polarity = 0 = active when High)
//Perform the main checks to see if nitrous is ready //Perform the main checks to see if nitrous is ready
if( (isArmed == true) && (currentStatus.coolant > (configPage10.n2o_minCLT - CALIBRATION_TEMPERATURE_OFFSET)) && (currentStatus.TPS > configPage10.n2o_minTPS) && (currentStatus.O2 < configPage10.n2o_maxAFR) && (currentStatus.MAP < configPage10.n2o_maxMAP) ) if( (isArmed == true) && (currentStatus.coolant > (configPage10.n2o_minCLT - CALIBRATION_TEMPERATURE_OFFSET)) && (currentStatus.TPS > configPage10.n2o_minTPS) && (currentStatus.O2 < configPage10.n2o_maxAFR) && (currentStatus.MAP < configPage10.n2o_maxMAP) )
{ {
uint16_t realStage1MinRPM = configPage10.n2o_stage1_minRPM * 100; uint16_t realStage1MinRPM = (uint16_t)configPage10.n2o_stage1_minRPM * 100;
uint16_t realStage1MaxRPM = configPage10.n2o_stage1_maxRPM * 100; uint16_t realStage1MaxRPM = (uint16_t)configPage10.n2o_stage1_maxRPM * 100;
uint16_t realStage2MinRPM = configPage10.n2o_stage2_minRPM * 100; uint16_t realStage2MinRPM = (uint16_t)configPage10.n2o_stage2_minRPM * 100;
uint16_t realStage2MaxRPM = configPage10.n2o_stage2_maxRPM * 100; uint16_t realStage2MaxRPM = (uint16_t)configPage10.n2o_stage2_maxRPM * 100;
if( (currentStatus.RPM > realStage1MinRPM) && (currentStatus.RPM < realStage1MaxRPM) ) if( (currentStatus.RPM > realStage1MinRPM) && (currentStatus.RPM < realStage1MaxRPM) )
{ {
currentStatus.nitrous_status = NITROUS_STAGE1; currentStatus.nitrous_status = NITROUS_STAGE1;
BIT_SET(currentStatus.status3, BIT_STATUS3_NITROUS); BIT_SET(currentStatus.status3, BIT_STATUS3_NITROUS);
digitalWrite(configPage10.n2o_stage1_pin, HIGH); N2O_STAGE1_PIN_HIGH();
nitrousOn = true;
} }
if( (currentStatus.RPM > realStage2MinRPM) && (currentStatus.RPM < realStage2MaxRPM) ) if(configPage10.n2o_enable == NITROUS_STAGE2) //This is really just a sanity check
{ {
currentStatus.nitrous_status = NITROUS_STAGE2; if( (currentStatus.RPM > realStage2MinRPM) && (currentStatus.RPM < realStage2MaxRPM) )
BIT_SET(currentStatus.status3, BIT_STATUS3_NITROUS); {
digitalWrite(configPage10.n2o_stage2_pin, HIGH); currentStatus.nitrous_status = NITROUS_STAGE2;
BIT_SET(currentStatus.status3, BIT_STATUS3_NITROUS);
N2O_STAGE2_PIN_HIGH();
nitrousOn = true;
}
} }
} }
else }
if (nitrousOn == false)
{ {
currentStatus.nitrous_status = NITROUS_OFF; currentStatus.nitrous_status = NITROUS_OFF;
BIT_CLEAR(currentStatus.status3, BIT_STATUS3_NITROUS); BIT_CLEAR(currentStatus.status3, BIT_STATUS3_NITROUS);
digitalWrite(configPage10.n2o_stage1_pin, LOW); N2O_STAGE1_PIN_LOW();
digitalWrite(configPage10.n2o_stage2_pin, LOW); N2O_STAGE2_PIN_LOW();
} }
}
} }
void boostDisable() void boostDisable()

View File

@ -132,7 +132,7 @@ void command()
break; break;
case 'Q': // send code version case 'Q': // send code version
Serial.print("speeduino 201806-dev"); Serial.print("speeduino 201806");
break; break;
case 'r': //New format for the optimised OutputChannels case 'r': //New format for the optimised OutputChannels
@ -162,7 +162,7 @@ void command()
break; break;
case 'S': // send code version case 'S': // send code version
Serial.print("Speeduino 2018.6-dev"); Serial.print("Speeduino 2018.6");
currentStatus.secl = 0; //This is required in TS3 due to its stricter timings currentStatus.secl = 0; //This is required in TS3 due to its stricter timings
break; break;

7
speeduino/crankMaths.h Normal file
View File

@ -0,0 +1,7 @@
#define CRANKMATH_METHOD_INTERVAL_RPM 0
#define CRANKMATH_METHOD_INTERVAL_TOOTH 1
#define CRANKMATH_METHOD_ALPHA_BETA 2
#define CRANKMATH_METHOD_2ND_DERIVATIVE 3
unsigned long angleToTime(int16_t angle);
uint16_t timeToAngle(unsigned long time);

43
speeduino/crankMaths.ino Normal file
View File

@ -0,0 +1,43 @@
/*
* Converts a crank angle into a time from or since that angle occurred.
* Positive angles are assumed to be in the future, negative angles in the past:
* * Future angle calculations will use a predicted speed/acceleration
* * Past angle calculations will use the known speed
*
* Multiple prediction methods will be implemented here for testing:
* * Last interval using both last full revolution and gap between last teeth
* * 2nd derivative prediction (Speed + acceleration)
* * Closed loop error correction (Alpha-beta filter).
*/
#define fastDegreesToUS(degrees) (degrees * (unsigned long)timePerDegree)
unsigned long angleToTime(int16_t angle)
{
//#define degreesToUS(degrees) (decoderIsLowRes == true ) ? ((degrees * 166666UL) / currentStatus.RPM) : (degrees * (unsigned long)timePerDegree)
//#define degreesToUS(degrees) ((degrees * revolutionTime) / 360)
//Fast version of divide by 360:
//#define degreesToUS(degrees) ((degrees * revolutionTime * 3054198967ULL) >> 40)
//#define degreesToUS(degrees) (degrees * (unsigned long)timePerDegree)
return ((angle * revolutionTime) / 360);
}
/*
* Convert a time (uS) into an angle at current speed
*/
uint16_t timeToAngle(unsigned long time)
{
//#define uSToDegrees(time) (((unsigned long)time * currentStatus.RPM) / 166666)
//Crazy magic numbers method from Hackers delight (www.hackersdelight.org/magic.htm):
//#define uSToDegrees(time) ( (((uint64_t)time * currentStatus.RPM * 211107077ULL) >> 45) )
return (((unsigned long)time * currentStatus.RPM) / 166666);
/*
switch(calculationAlgorithm)
{
case CRANKMATH_METHOD_INTERVAL_TOOTH:
returnValue = ((elapsedTime * triggerToothAngle) / toothTime);
}
*/
}

View File

@ -44,8 +44,7 @@ As nearly all the decoders use a common method of determining RPM (The time the
A common function is simpler A common function is simpler
degreesOver is the number of crank degrees between tooth #1s. Some patterns have a tooth #1 every crank rev, others are every cam rev. degreesOver is the number of crank degrees between tooth #1s. Some patterns have a tooth #1 every crank rev, others are every cam rev.
*/ */
static inline uint16_t stdGetRPM(uint16_t degreesOver=360) static inline uint16_t stdGetRPM(uint16_t degreesOver)
//static inline uint16_t stdGetRPM()
{ {
uint16_t tempRPM = 0; uint16_t tempRPM = 0;
@ -247,7 +246,7 @@ uint16_t getRPM_missingTooth()
else else
{ {
if(configPage4.TrigSpeed == CAM_SPEED) { tempRPM = stdGetRPM(720); } //Account for cam speed if(configPage4.TrigSpeed == CAM_SPEED) { tempRPM = stdGetRPM(720); } //Account for cam speed
else { tempRPM = stdGetRPM(); } else { tempRPM = stdGetRPM(360); }
} }
return tempRPM; return tempRPM;
} }
@ -396,7 +395,7 @@ uint16_t getRPM_DualWheel()
if( currentStatus.hasSync == true ) if( currentStatus.hasSync == true )
{ {
if(currentStatus.RPM < currentStatus.crankRPM) { tempRPM = crankingGetRPM(configPage4.triggerTeeth); } if(currentStatus.RPM < currentStatus.crankRPM) { tempRPM = crankingGetRPM(configPage4.triggerTeeth); }
else { tempRPM = stdGetRPM(); } else { tempRPM = stdGetRPM(360); }
} }
return tempRPM; return tempRPM;
} }
@ -534,7 +533,7 @@ uint16_t getRPM_BasicDistributor()
uint16_t tempRPM; uint16_t tempRPM;
if( currentStatus.RPM < currentStatus.crankRPM ) if( currentStatus.RPM < currentStatus.crankRPM )
{ tempRPM = crankingGetRPM(triggerActualTeeth) << 1; } //crankGetRPM uses teeth per 360 degrees. As triggerActualTeeh is total teeth in 720 degrees, we divide the tooth count by 2 { tempRPM = crankingGetRPM(triggerActualTeeth) << 1; } //crankGetRPM uses teeth per 360 degrees. As triggerActualTeeh is total teeth in 720 degrees, we divide the tooth count by 2
else { tempRPM = stdGetRPM() << 1; } //Multiply RPM by 2 due to tracking over 720 degrees now rather than 360 else { tempRPM = stdGetRPM(720); } //Multiply RPM by 2 due to tracking over 720 degrees now rather than 360
revolutionTime = revolutionTime >> 1; //Revolution time has to be divided by 2 as otherwise it would be over 720 degrees (triggerActualTeeth = nCylinders) revolutionTime = revolutionTime >> 1; //Revolution time has to be divided by 2 as otherwise it would be over 720 degrees (triggerActualTeeth = nCylinders)
MAX_STALL_TIME = revolutionTime << 1; //Set the stall time to be twice the current RPM. This is a safe figure as there should be no single revolution where this changes more than this MAX_STALL_TIME = revolutionTime << 1; //Set the stall time to be twice the current RPM. This is a safe figure as there should be no single revolution where this changes more than this
@ -627,7 +626,7 @@ void triggerPri_GM7X()
void triggerSec_GM7X() { return; } //Not required void triggerSec_GM7X() { return; } //Not required
uint16_t getRPM_GM7X() uint16_t getRPM_GM7X()
{ {
return stdGetRPM(); return stdGetRPM(360);
} }
int getCrankAngle_GM7X(int timePerDegree) int getCrankAngle_GM7X(int timePerDegree)
{ {
@ -1032,7 +1031,7 @@ uint16_t getRPM_4G63()
} }
else else
{ {
if(configPage2.nCylinders == 4) { tempRPM = stdGetRPM(); } if(configPage2.nCylinders == 4) { tempRPM = stdGetRPM(360); }
else if(configPage2.nCylinders == 6) { tempRPM = stdGetRPM(720); } else if(configPage2.nCylinders == 6) { tempRPM = stdGetRPM(720); }
//EXPERIMENTAL! Add/subtract RPM based on the last rpmDOT calc //EXPERIMENTAL! Add/subtract RPM based on the last rpmDOT calc
//tempRPM += (micros() - toothOneTime) * currentStatus.rpmDOT //tempRPM += (micros() - toothOneTime) * currentStatus.rpmDOT
@ -1164,7 +1163,7 @@ void triggerSec_24X()
uint16_t getRPM_24X() uint16_t getRPM_24X()
{ {
return stdGetRPM(); return stdGetRPM(360);
} }
int getCrankAngle_24X(int timePerDegree) int getCrankAngle_24X(int timePerDegree)
{ {
@ -1270,7 +1269,7 @@ void triggerSec_Jeep2000()
uint16_t getRPM_Jeep2000() uint16_t getRPM_Jeep2000()
{ {
return stdGetRPM(); return stdGetRPM(360);
} }
int getCrankAngle_Jeep2000(int timePerDegree) int getCrankAngle_Jeep2000(int timePerDegree)
{ {
@ -1382,7 +1381,7 @@ void triggerSec_Audi135()
uint16_t getRPM_Audi135() uint16_t getRPM_Audi135()
{ {
return stdGetRPM(); return stdGetRPM(360);
} }
int getCrankAngle_Audi135(int timePerDegree) int getCrankAngle_Audi135(int timePerDegree)
@ -1479,7 +1478,7 @@ void triggerPri_HondaD17()
void triggerSec_HondaD17() { return; } //The 4+1 signal on the cam is yet to be supported void triggerSec_HondaD17() { return; } //The 4+1 signal on the cam is yet to be supported
uint16_t getRPM_HondaD17() uint16_t getRPM_HondaD17()
{ {
return stdGetRPM(); return stdGetRPM(360);
} }
int getCrankAngle_HondaD17(int timePerDegree) int getCrankAngle_HondaD17(int timePerDegree)
{ {
@ -1683,7 +1682,7 @@ uint16_t getRPM_Miata9905()
} }
else else
{ {
tempRPM = stdGetRPM() << 1; tempRPM = stdGetRPM(720);
revolutionTime = revolutionTime / 2; revolutionTime = revolutionTime / 2;
MAX_STALL_TIME = revolutionTime << 1; //Set the stall time to be twice the current RPM. This is a safe figure as there should be no single revolution where this changes more than this MAX_STALL_TIME = revolutionTime << 1; //Set the stall time to be twice the current RPM. This is a safe figure as there should be no single revolution where this changes more than this
if(MAX_STALL_TIME < 366667UL) { MAX_STALL_TIME = 366667UL; } //Check for 50rpm minimum if(MAX_STALL_TIME < 366667UL) { MAX_STALL_TIME = 366667UL; } //Check for 50rpm minimum
@ -1840,7 +1839,7 @@ uint16_t getRPM_MazdaAU()
revolutionTime = revolutionTime * 36; revolutionTime = revolutionTime * 36;
tempRPM = (tempToothAngle * 60000000L) / revolutionTime; tempRPM = (tempToothAngle * 60000000L) / revolutionTime;
} }
else { tempRPM = stdGetRPM(); } else { tempRPM = stdGetRPM(360); }
} }
return tempRPM; return tempRPM;
} }
@ -1912,7 +1911,7 @@ uint16_t getRPM_non360()
if( (currentStatus.hasSync == true) && (toothCurrentCount != 0) ) if( (currentStatus.hasSync == true) && (toothCurrentCount != 0) )
{ {
if(currentStatus.RPM < currentStatus.crankRPM) { tempRPM = crankingGetRPM(configPage4.triggerTeeth); } if(currentStatus.RPM < currentStatus.crankRPM) { tempRPM = crankingGetRPM(configPage4.triggerTeeth); }
else { tempRPM = stdGetRPM(); } else { tempRPM = stdGetRPM(360); }
} }
return tempRPM; return tempRPM;
} }
@ -2279,7 +2278,7 @@ uint16_t getRPM_Subaru67()
if(currentStatus.startRevolutions > 0) if(currentStatus.startRevolutions > 0)
{ {
//As the tooth count is over 720 degrees, we need to double the RPM value and halve the revolution time //As the tooth count is over 720 degrees, we need to double the RPM value and halve the revolution time
tempRPM = stdGetRPM() << 1; tempRPM = stdGetRPM(720);
revolutionTime = revolutionTime >> 1; //Revolution time has to be divided by 2 as otherwise it would be over 720 degrees (triggerActualTeeth = nCylinders) revolutionTime = revolutionTime >> 1; //Revolution time has to be divided by 2 as otherwise it would be over 720 degrees (triggerActualTeeth = nCylinders)
} }
return tempRPM; return tempRPM;
@ -2446,7 +2445,7 @@ uint16_t getRPM_Daihatsu()
else { tempRPM = 0; } //No sync else { tempRPM = 0; } //No sync
} }
else else
{ tempRPM = stdGetRPM() << 1; } //Multiply RPM by 2 due to tracking over 720 degrees now rather than 360 { tempRPM = stdGetRPM(720); } //TRacking over 2 crank revolutions
return tempRPM; return tempRPM;
@ -2575,7 +2574,7 @@ uint16_t getRPM_Harley()
} }
} }
else { else {
tempRPM = stdGetRPM(); tempRPM = stdGetRPM(360);
} }
} }
return tempRPM; return tempRPM;

View File

@ -221,7 +221,7 @@ struct table2D flexFuelTable; //6 bin flex fuel correction table for fuel adjus
struct table2D flexAdvTable; //6 bin flex fuel correction table for timing advance (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) 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 //These are for the direct port manipulation of the injectors, coils and aux outputs
volatile byte *inj1_pin_port; volatile byte *inj1_pin_port;
volatile byte inj1_pin_mask; volatile byte inj1_pin_mask;
volatile byte *inj2_pin_port; volatile byte *inj2_pin_port;

View File

@ -4,14 +4,6 @@
int fastMap1023toX(int, int); int fastMap1023toX(int, int);
unsigned long percentage(byte, unsigned long); unsigned long percentage(byte, unsigned long);
//#define degreesToUS(degrees) (decoderIsLowRes == true ) ? ((degrees * 166666UL) / currentStatus.RPM) : (degrees * (unsigned long)timePerDegree)
#define degreesToUS(degrees) ((degrees * revolutionTime) / 360)
#define fastDegreesToUS(degrees) (degrees * (unsigned long)timePerDegree)
//#define degreesToUS(degrees) ((degrees * revolutionTime * 3054198967ULL) >> 40) //Fast version of divide by 360
//#define degreesToUS(degrees) (degrees * (unsigned long)timePerDegree)
#define uSToDegrees(time) (((unsigned long)time * currentStatus.RPM) / 166666)
//#define uSToDegrees(time) ( (((uint64_t)time * currentStatus.RPM * 211107077ULL) >> 45) ) //Crazy magic numbers method from Hackers delight (www.hackersdelight.org/magic.htm)
#define DIV_ROUND_CLOSEST(n, d) ((((n) < 0) ^ ((d) < 0)) ? (((n) - (d)/2)/(d)) : (((n) + (d)/2)/(d))) #define DIV_ROUND_CLOSEST(n, d) ((((n) < 0) ^ ((d) < 0)) ? (((n) - (d)/2)/(d)) : (((n) + (d)/2)/(d)))
//This is a dedicated function that specifically handles the case of mapping 0-1023 values into a 0 to X range //This is a dedicated function that specifically handles the case of mapping 0-1023 values into a 0 to X range

View File

@ -949,7 +949,6 @@ void loop()
//Most boost tends to run at about 30Hz, so placing it here ensures a new target time is fetched frequently enough //Most boost tends to run at about 30Hz, so placing it here ensures a new target time is fetched frequently enough
//currentStatus.RPM = 3000; //currentStatus.RPM = 3000;
boostControl(); boostControl();
nitrousControl();
} }
//The IAT and CLT readings can be done less frequently (4 times per second) //The IAT and CLT readings can be done less frequently (4 times per second)
if (BIT_CHECK(LOOP_TIMER, BIT_TIMER_4HZ)) if (BIT_CHECK(LOOP_TIMER, BIT_TIMER_4HZ))
@ -960,6 +959,7 @@ void loop()
readO2(); readO2();
readO2_2(); readO2_2();
readBat(); readBat();
nitrousControl();
if(eepromWritesPending == true) { writeAllConfig(); } //Check for any outstanding EEPROM writes. if(eepromWritesPending == true) { writeAllConfig(); } //Check for any outstanding EEPROM writes.
@ -1073,15 +1073,17 @@ void loop()
//Manual adder for nitrous. These are not in correctionsFuel() because they are direct adders to the ms value, not % based //Manual adder for nitrous. These are not in correctionsFuel() because they are direct adders to the ms value, not % based
if(currentStatus.nitrous_status == NITROUS_STAGE1) if(currentStatus.nitrous_status == NITROUS_STAGE1)
{ {
int16_t adderRange = configPage10.n2o_stage1_maxRPM - configPage10.n2o_stage1_minRPM; int16_t adderRange = (configPage10.n2o_stage1_maxRPM - configPage10.n2o_stage1_minRPM) * 100;
int16_t adderPercent = ((currentStatus.RPM - configPage10.n2o_stage1_minRPM) * 100) / adderRange; //The percentage of the way through the RPM range int16_t adderPercent = ((currentStatus.RPM - (configPage10.n2o_stage1_minRPM * 100)) * 100) / adderRange; //The percentage of the way through the RPM range
currentStatus.PW1 = currentStatus.PW1 + configPage10.n2o_stage1_adderMax + percentage(adderPercent, (configPage10.n2o_stage1_adderMin - configPage10.n2o_stage1_adderMax)); //Calculate the above percentage of the calculated ms value. adderPercent = 100 - adderPercent; //Flip the percentage as we go from a higher adder to a lower adder as the RPMs rise
currentStatus.PW1 = currentStatus.PW1 + (configPage10.n2o_stage1_adderMax + percentage(adderPercent, (configPage10.n2o_stage1_adderMin - configPage10.n2o_stage1_adderMax))) * 100; //Calculate the above percentage of the calculated ms value.
} }
if(currentStatus.nitrous_status == NITROUS_STAGE2) if(currentStatus.nitrous_status == NITROUS_STAGE2)
{ {
int16_t adderRange = configPage10.n2o_stage2_maxRPM - configPage10.n2o_stage2_minRPM; int16_t adderRange = (configPage10.n2o_stage2_maxRPM - configPage10.n2o_stage2_minRPM) * 100;
int16_t adderPercent = ((currentStatus.RPM - configPage10.n2o_stage2_minRPM) * 100) / adderRange; //The percentage of the way through the RPM range int16_t adderPercent = ((currentStatus.RPM - (configPage10.n2o_stage2_minRPM * 100)) * 100) / adderRange; //The percentage of the way through the RPM range
currentStatus.PW1 = currentStatus.PW1 + configPage10.n2o_stage2_adderMax + percentage(adderPercent, (configPage10.n2o_stage2_adderMin - configPage10.n2o_stage2_adderMax)); //Calculate the above percentage of the calculated ms value. adderPercent = 100 - adderPercent; //Flip the percentage as we go from a higher adder to a lower adder as the RPMs rise
currentStatus.PW1 = currentStatus.PW1 + (configPage10.n2o_stage2_adderMax + percentage(adderPercent, (configPage10.n2o_stage2_adderMin - configPage10.n2o_stage2_adderMax))) * 100; //Calculate the above percentage of the calculated ms value.
} }
int injector1StartAngle = 0; int injector1StartAngle = 0;