Experimental commit of per tooth based ignition timing
This commit is contained in:
parent
7f86b91198
commit
5992e31f2f
|
@ -213,7 +213,7 @@ page = 2
|
|||
algorithm = bits, U08, 38, [2:2], "Speed Density", "Alpha-N"
|
||||
baroCorr = bits, U08, 38, [3:3], "Off", "On"
|
||||
injLayout = bits, U08, 38, [4:5], "Paired", "Semi-Sequential", "INVALID", "Sequential"
|
||||
unused2-38f= bits, U08, 38, [6:6], "ONE", "INVALID"
|
||||
perToothIgn= bits, U08, 38, [6:6], "No", "Yes"
|
||||
unused2-38h= bits, U08, 38, [7:7], "No", "Yes"
|
||||
|
||||
primePulse = scalar, U08, 39, "ms", 0.1, 0.0, 0.0, 25.5, 1
|
||||
|
@ -570,22 +570,39 @@ page = 10
|
|||
caninput_sel15 = bits, U16, 1, [15:15], "Off", "On"
|
||||
|
||||
;caninput_param_group = array , U16, 9, [ 8], "", 1, 0, 0, 65535, 0
|
||||
caninput_param_group0 = bits, U16, 3, [0:10], $CAN_ADDRESS_HEX
|
||||
caninput_param_group1 = bits, U16, 5, [0:10], $CAN_ADDRESS_HEX
|
||||
caninput_param_group2 = bits, U16, 7, [0:10], $CAN_ADDRESS_HEX
|
||||
caninput_param_group3 = bits, U16, 9, [0:10], $CAN_ADDRESS_HEX
|
||||
caninput_param_group4 = bits, U16, 11, [0:10], $CAN_ADDRESS_HEX
|
||||
caninput_param_group5 = bits, U16, 13, [0:10], $CAN_ADDRESS_HEX
|
||||
caninput_param_group6 = bits, U16, 15, [0:10], $CAN_ADDRESS_HEX
|
||||
caninput_param_group7 = bits, U16, 17, [0:10], $CAN_ADDRESS_HEX
|
||||
caninput_param_group8 = bits, U16, 19, [0:10], $CAN_ADDRESS_HEX
|
||||
caninput_param_group9 = bits, U16, 21, [0:10], $CAN_ADDRESS_HEX
|
||||
caninput_param_group10 = bits, U16, 23, [0:10], $CAN_ADDRESS_HEX
|
||||
caninput_param_group11 = bits, U16, 25, [0:10], $CAN_ADDRESS_HEX
|
||||
caninput_param_group12 = bits, U16, 27, [0:10], $CAN_ADDRESS_HEX
|
||||
caninput_param_group13 = bits, U16, 29, [0:10], $CAN_ADDRESS_HEX
|
||||
caninput_param_group14 = bits, U16, 31, [0:10], $CAN_ADDRESS_HEX
|
||||
caninput_param_group15 = bits, U16, 33, [0:10], $CAN_ADDRESS_HEX
|
||||
;caninput_param_group0 = bits, U16, 3, [0:10], $CAN_ADDRESS_HEX_01XX
|
||||
;caninput_param_group1 = bits, U16, 5, [0:10], $CAN_ADDRESS_HEX_01XX
|
||||
;caninput_param_group2 = bits, U16, 7, [0:10], $CAN_ADDRESS_HEX_01XX
|
||||
;caninput_param_group3 = bits, U16, 9, [0:10], $CAN_ADDRESS_HEX_01XX
|
||||
;caninput_param_group4 = bits, U16, 11, [0:10], $CAN_ADDRESS_HEX_01XX
|
||||
;caninput_param_group5 = bits, U16, 13, [0:10], $CAN_ADDRESS_HEX_01XX
|
||||
;caninput_param_group6 = bits, U16, 15, [0:10], $CAN_ADDRESS_HEX_01XX
|
||||
;caninput_param_group7 = bits, U16, 17, [0:10], $CAN_ADDRESS_HEX_01XX
|
||||
;caninput_param_group8 = bits, U16, 19, [0:10], $CAN_ADDRESS_HEX_01XX
|
||||
;caninput_param_group9 = bits, U16, 21, [0:10], $CAN_ADDRESS_HEX_01XX
|
||||
;caninput_param_group10 = bits, U16, 23, [0:10], $CAN_ADDRESS_HEX_01XX
|
||||
;caninput_param_group11 = bits, U16, 25, [0:10], $CAN_ADDRESS_HEX_01XX
|
||||
;caninput_param_group12 = bits, U16, 27, [0:10], $CAN_ADDRESS_HEX_01XX
|
||||
;caninput_param_group13 = bits, U16, 29, [0:10], $CAN_ADDRESS_HEX_01XX
|
||||
;caninput_param_group14 = bits, U16, 31, [0:10], $CAN_ADDRESS_HEX_01XX
|
||||
;caninput_param_group15 = bits, U16, 33, [0:10], $CAN_ADDRESS_HEX_01XX
|
||||
|
||||
caninput_param_group0 = scalar, U16, 3, "", 1, 0, 0, 255, 0
|
||||
caninput_param_group1 = scalar, U16, 5, "", 1, 0, 0, 255, 0
|
||||
caninput_param_group2 = scalar, U16, 7, "", 1, 0, 0, 255, 0
|
||||
caninput_param_group3 = scalar, U16, 9, "", 1, 0, 0, 255, 0
|
||||
caninput_param_group4 = scalar, U16, 11, "", 1, 0, 0, 255, 0
|
||||
caninput_param_group5 = scalar, U16, 13, "", 1, 0, 0, 255, 0
|
||||
caninput_param_group6 = scalar, U16, 15, "", 1, 0, 0, 255, 0
|
||||
caninput_param_group7 = scalar, U16, 17, "", 1, 0, 0, 255, 0
|
||||
caninput_param_group8 = scalar, U16, 19, "", 1, 0, 0, 255, 0
|
||||
caninput_param_group9 = scalar, U16, 21, "", 1, 0, 0, 255, 0
|
||||
caninput_param_group10 = scalar, U16, 23, "", 1, 0, 0, 255, 0
|
||||
caninput_param_group11 = scalar, U16, 25, "", 1, 0, 0, 255, 0
|
||||
caninput_param_group12 = scalar, U16, 27, "", 1, 0, 0, 255, 0
|
||||
caninput_param_group13 = scalar, U16, 29, "", 1, 0, 0, 255, 0
|
||||
caninput_param_group14 = scalar, U16, 31, "", 1, 0, 0, 255, 0
|
||||
caninput_param_group15 = scalar, U16, 33, "", 1, 0, 0, 255, 0
|
||||
|
||||
caninput_param_start_byte0 = bits, U08, 35, [0:2], "0", "1", "2", "3", "4", "5", "6", "7"
|
||||
caninput_param_start_byte1 = bits, U08, 36, [0:2], "0", "1", "2", "3", "4", "5", "6", "7"
|
||||
|
@ -655,13 +672,14 @@ page = 10
|
|||
unused10_99 = scalar, U08, 99, "", 1, 0, 0, 255, 0
|
||||
|
||||
speeduino_tsCanId = bits, U08, 100, [0:3], $tsCanId_list
|
||||
true_address = bits, U16, 101, [0:10], $CAN_ADDRESS_HEX
|
||||
realtime_base_address = bits, U16, 103, [0:10], $CAN_ADDRESS_HEX
|
||||
obd_address = bits, U16, 105, [0:10], $CAN_ADDRESS_HEX
|
||||
;true_address = bits, U16, 101, [0:10], $CAN_ADDRESS_HEX
|
||||
;realtime_base_address = bits, U16, 103, [0:10], $CAN_ADDRESS_HEX
|
||||
;obd_address = bits, U16, 105, [0:10], $CAN_ADDRESS_HEX
|
||||
|
||||
;unused10_101 = scalar, U16, 101, "", 1, 0, 0, 255, 0
|
||||
;unused10_103 = scalar, U16, 103, "", 1, 0, 0, 255, 0
|
||||
;unused10_105 = scalar, U16, 105, "", 1, 0, 0, 255, 0
|
||||
|
||||
unused10_101 = scalar, U16, 101, "", 1, 0, 0, 255, 0
|
||||
unused10_103 = scalar, U16, 103, "", 1, 0, 0, 255, 0
|
||||
unused10_105 = scalar, U16, 105, "", 1, 0, 0, 255, 0
|
||||
|
||||
;AFR offset for WUE VeAnalyze
|
||||
;wueAFRRates = array, U08, 107, [10], "%", 1.0, 0.0, 0.0, 255, 0
|
||||
|
@ -770,6 +788,7 @@ page = 10
|
|||
defaultValue = boostPin, 0
|
||||
defaultValue = fuelPumpPin, 0
|
||||
defaultValue = tachoPin, 0
|
||||
defaultValue = perToothIgn, 0
|
||||
[Menu]
|
||||
|
||||
;----------------------------------------------------------------------------
|
||||
|
@ -1265,6 +1284,9 @@ menuDialog = main
|
|||
field = "Secondary trigger edge", TrigEdgeSec, { TrigPattern == 0 || TrigPattern == 2 } ;Missing tooth and dual wheel
|
||||
field = "Trigger Filter", TrigFilter
|
||||
field = "Re-sync every cycle", useResync, { TrigPattern == 2 || TrigPattern == 4 || TrigPattern == 7 } ;Dual wheel, 4G63 and Audi 135
|
||||
field = ""
|
||||
field = "#The below option is EXPERIMENTAL! If unsure what this is, please set to No"
|
||||
field = "User per tooth ignition calculation", perToothIgn, {TrigPattern == 0} ;Only works for missing tooth
|
||||
|
||||
dialog = sparkSettings,"Spark Settings",4
|
||||
field = "Spark output mode", sparkMode
|
||||
|
|
|
@ -61,6 +61,11 @@ bool secondDerivEnabled; //The use of the 2nd derivative calculation is limited
|
|||
bool decoderIsSequential; //Whether or not the decoder supports sequential operation
|
||||
byte checkSyncToothCount; //How many teeth must've been seen on this revolution before we try to confirm sync (Useful for missing tooth type decoders)
|
||||
|
||||
int ignition1EndTooth = 0;
|
||||
int ignition2EndTooth = 0;
|
||||
int ignition3EndTooth = 0;
|
||||
int ignition4EndTooth = 0;
|
||||
|
||||
int toothAngles[24]; //An array for storing fixed tooth angles. Currently sized at 24 for the GM 24X decoder, but may grow later if there are other decoders that use this style
|
||||
|
||||
//Used for identifying long and short pulses on the 4G63 (And possibly other) trigger patterns
|
||||
|
|
|
@ -161,7 +161,20 @@ void triggerPri_missingTooth()
|
|||
}
|
||||
}
|
||||
|
||||
//EXPERIMENTAL!
|
||||
if(configPage1.perToothIgn == true)
|
||||
{
|
||||
uint16_t crankAngle = (toothCurrentCount-1) * triggerToothAngle + configPage2.triggerAngle;
|
||||
if ( (toothCurrentCount == ignition1EndTooth) && (ignitionSchedule1.Status == RUNNING) )
|
||||
{
|
||||
IGN1_COMPARE = IGN1_COUNTER + uS_TO_TIMER_COMPARE( (ignition1EndAngle - crankAngle) * timePerDegree );
|
||||
//IGN1_COMPARE = IGN1_COUNTER + uS_TO_TIMER_COMPARE( (ignition1EndAngle - crankAngle)*my_timePerDegree - micros_compensation ); //OCR5A = TCNT5 + (ignitionSchedule1.duration >> 2); //Divide by 4
|
||||
|
||||
}
|
||||
else if ( toothCurrentCount == ignition2EndTooth && (ignitionSchedule2.Status == RUNNING) ) { IGN2_COMPARE = IGN2_COUNTER + uS_TO_TIMER_COMPARE( (ignition2EndAngle - crankAngle) * timePerDegree ); }
|
||||
else if ( toothCurrentCount == ignition3EndTooth && (ignitionSchedule3.Status == RUNNING) ) { IGN3_COMPARE = IGN3_COUNTER + uS_TO_TIMER_COMPARE( (ignition3EndAngle - crankAngle) * timePerDegree ); }
|
||||
else if ( toothCurrentCount == ignition4EndTooth && (ignitionSchedule4.Status == RUNNING) ) { IGN4_COMPARE = IGN4_COUNTER + uS_TO_TIMER_COMPARE( (ignition4EndAngle - crankAngle) * timePerDegree ); }
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -217,6 +230,14 @@ int getCrankAngle_missingTooth(int timePerDegree)
|
|||
return crankAngle;
|
||||
}
|
||||
|
||||
void triggerSetEndTeeth_missingTooth()
|
||||
{
|
||||
ignition1EndTooth = (ignition1EndAngle - configPage2.triggerAngle) / triggerToothAngle - 1;
|
||||
ignition2EndTooth = (ignition2EndAngle - configPage2.triggerAngle) / triggerToothAngle - 1;
|
||||
ignition3EndTooth = (ignition3EndAngle - configPage2.triggerAngle) / triggerToothAngle - 1;
|
||||
ignition4EndTooth = (ignition4EndAngle - configPage2.triggerAngle) / triggerToothAngle - 1;
|
||||
}
|
||||
|
||||
/* -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
|
||||
Name: Dual wheel
|
||||
Desc: 2 wheels located either both on the crank or with the primary on the crank and the secondary on the cam.
|
||||
|
@ -330,6 +351,11 @@ int getCrankAngle_DualWheel(int timePerDegree)
|
|||
return crankAngle;
|
||||
}
|
||||
|
||||
void triggerSetEndTeeth_DualWheel()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
|
||||
/* -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
|
||||
Name: Basic Distributor
|
||||
|
@ -421,6 +447,11 @@ int getCrankAngle_BasicDistributor(int timePerDegree)
|
|||
return crankAngle;
|
||||
}
|
||||
|
||||
void triggerSetEndTeeth_BasicDistributor()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
/* -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
|
||||
Name: GM7X
|
||||
Desc: GM 7X trigger wheel. It has six equally spaced teeth and a seventh tooth for cylinder identification.
|
||||
|
@ -512,6 +543,11 @@ int getCrankAngle_GM7X(int timePerDegree)
|
|||
return crankAngle;
|
||||
}
|
||||
|
||||
void triggerSetEndTeeth_GM7X()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
|
||||
/* -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
|
||||
Name: Mitsubishi 4G63 / NA/NB Miata + MX-5 / 4/2
|
||||
|
@ -746,6 +782,11 @@ int getCrankAngle_4G63(int timePerDegree)
|
|||
return crankAngle;
|
||||
}
|
||||
|
||||
void triggerSetEndTeeth_4G63()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
/* -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
|
||||
Name: GM
|
||||
Desc: TBA
|
||||
|
@ -851,6 +892,11 @@ int getCrankAngle_24X(int timePerDegree)
|
|||
return crankAngle;
|
||||
}
|
||||
|
||||
void triggerSetEndTeeth_24X()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
/* -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
|
||||
Name: Jeep 2000
|
||||
Desc: For '91 to 2000 6 cylinder Jeep engines
|
||||
|
@ -947,7 +993,12 @@ int getCrankAngle_Jeep2000(int timePerDegree)
|
|||
return crankAngle;
|
||||
}
|
||||
|
||||
/*
|
||||
void triggerSetEndTeeth_Jeep2000()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
/* -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
|
||||
Name: Audi 135
|
||||
Desc: 135 teeth on the crank and 1 tooth on the cam.
|
||||
Note: This is very similar to the dual wheel decoder, however due to the 135 teeth not dividing evenly into 360, only every 3rd crank tooth is used in calculating the crank angle. This effectively makes it a 45 tooth dual wheel setup
|
||||
|
@ -1059,6 +1110,11 @@ int getCrankAngle_Audi135(int timePerDegree)
|
|||
return crankAngle;
|
||||
}
|
||||
|
||||
void triggerSetEndTeeth_Audi135()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
/* -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
|
||||
Name: Honda D17
|
||||
Desc:
|
||||
|
@ -1152,6 +1208,11 @@ int getCrankAngle_HondaD17(int timePerDegree)
|
|||
return crankAngle;
|
||||
}
|
||||
|
||||
void triggerSetEndTeeth_HondaD17()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
/* -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
|
||||
Name: Miata '99 to '05
|
||||
Desc: TBA (See: http://forum.diyefi.org/viewtopic.php?f=56&t=1077)
|
||||
|
@ -1233,7 +1294,6 @@ void triggerSec_Miata9905()
|
|||
}
|
||||
}
|
||||
|
||||
|
||||
uint16_t getRPM_Miata9905()
|
||||
{
|
||||
//During cranking, RPM is calculated 4 times per revolution, once for each tooth on the crank signal.
|
||||
|
@ -1283,6 +1343,11 @@ int getCrankAngle_Miata9905(int timePerDegree)
|
|||
return crankAngle;
|
||||
}
|
||||
|
||||
void triggerSetEndTeeth_Miata9905()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
/* -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
|
||||
Name: Mazda AU version
|
||||
Desc:
|
||||
|
@ -1431,6 +1496,11 @@ int getCrankAngle_MazdaAU(int timePerDegree)
|
|||
return crankAngle;
|
||||
}
|
||||
|
||||
void triggerSetEndTeeth_MazdaAU()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
/*
|
||||
Name: Non-360 Dual wheel
|
||||
Desc: 2 wheels located either both on the crank or with the primary on the crank and the secondary on the cam.
|
||||
|
@ -1499,6 +1569,11 @@ int getCrankAngle_non360(int timePerDegree)
|
|||
return crankAngle;
|
||||
}
|
||||
|
||||
void triggerSetEndTeeth_Non360()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
/* -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
|
||||
Name: Nissan 360 tooth with cam
|
||||
Desc:
|
||||
|
@ -1666,8 +1741,13 @@ int getCrankAngle_Nissan360(int timePerDegree)
|
|||
return crankAngle;
|
||||
}
|
||||
|
||||
void triggerSetEndTeeth_Nissan360()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
/* -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
|
||||
Name: Nissan 360 tooth with cam
|
||||
Name: Subary 6/7
|
||||
Desc:
|
||||
Note:
|
||||
*/
|
||||
|
@ -1810,6 +1890,11 @@ int getCrankAngle_Subaru67(int timePerDegree)
|
|||
return crankAngle;
|
||||
}
|
||||
|
||||
void triggerSetEndTeeth_Subaru67()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
/* -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
|
||||
Name: Daihatsu +1 trigger for 3 and 4 cylinder engines
|
||||
Desc: Tooth equal to the number of cylinders are evenly spaced on the cam. No position sensing (Distributor is retained) so crank angle is a made up figure based purely on the first teeth to be seen
|
||||
|
@ -1966,3 +2051,8 @@ int getCrankAngle_Daihatsu(int timePerDegree)
|
|||
|
||||
return crankAngle;
|
||||
}
|
||||
|
||||
void triggerSetEndTeeth_Daihatsu()
|
||||
{
|
||||
|
||||
}
|
||||
|
|
|
@ -165,6 +165,11 @@ bool channel3InjEnabled = false;
|
|||
bool channel4InjEnabled = false;
|
||||
bool channel5InjEnabled = false;
|
||||
|
||||
int ignition1EndAngle = 0;
|
||||
int ignition2EndAngle = 0;
|
||||
int ignition3EndAngle = 0;
|
||||
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)
|
||||
|
||||
|
@ -307,7 +312,7 @@ struct config1 {
|
|||
byte algorithm : 1; //"Speed Density", "Alpha-N"
|
||||
byte baroCorr : 1;
|
||||
byte injLayout : 2;
|
||||
byte unused2_38g : 1;
|
||||
byte perToothIgn : 1;
|
||||
byte unused2_38h : 1;
|
||||
|
||||
byte primePulse;
|
||||
|
|
|
@ -70,6 +70,7 @@ void (*trigger)(); //Pointer for the trigger function (Gets pointed to the relev
|
|||
void (*triggerSecondary)(); //Pointer for the secondary trigger function (Gets pointed to the relevant decoder)
|
||||
uint16_t (*getRPM)(); //Pointer to the getRPM function (Gets pointed to the relevant decoder)
|
||||
int (*getCrankAngle)(int); //Pointer to the getCrank Angle function (Gets pointed to the relevant decoder)
|
||||
void (*triggerSetEndTeeth)(); //Pointer to the triggerSetEndTeeth function of each decoder
|
||||
|
||||
byte cltCalibrationTable[CALIBRATION_TABLE_SIZE];
|
||||
byte iatCalibrationTable[CALIBRATION_TABLE_SIZE];
|
||||
|
@ -337,6 +338,7 @@ void setup()
|
|||
triggerSecondary = triggerSec_missingTooth;
|
||||
getRPM = getRPM_missingTooth;
|
||||
getCrankAngle = getCrankAngle_missingTooth;
|
||||
triggerSetEndTeeth = triggerSetEndTeeth_missingTooth;
|
||||
|
||||
if(configPage2.TrigEdge == 0) { attachInterrupt(triggerInterrupt, trigger, RISING); } // Attach the crank trigger wheel interrupt (Hall sensor drags to ground when triggering)
|
||||
else { attachInterrupt(triggerInterrupt, trigger, FALLING); }
|
||||
|
@ -350,6 +352,7 @@ void setup()
|
|||
trigger = triggerPri_BasicDistributor;
|
||||
getRPM = getRPM_BasicDistributor;
|
||||
getCrankAngle = getCrankAngle_BasicDistributor;
|
||||
triggerSetEndTeeth = triggerSetEndTeeth_BasicDistributor;
|
||||
|
||||
if(configPage2.TrigEdge == 0) { attachInterrupt(triggerInterrupt, trigger, RISING); } // Attach the crank trigger wheel interrupt (Hall sensor drags to ground when triggering)
|
||||
else { attachInterrupt(triggerInterrupt, trigger, FALLING); }
|
||||
|
@ -360,6 +363,7 @@ void setup()
|
|||
trigger = triggerPri_DualWheel;
|
||||
getRPM = getRPM_DualWheel;
|
||||
getCrankAngle = getCrankAngle_DualWheel;
|
||||
triggerSetEndTeeth = triggerSetEndTeeth_DualWheel;
|
||||
|
||||
if(configPage2.TrigEdge == 0) { attachInterrupt(triggerInterrupt, trigger, RISING); } // Attach the crank trigger wheel interrupt (Hall sensor drags to ground when triggering)
|
||||
else { attachInterrupt(triggerInterrupt, trigger, FALLING); }
|
||||
|
@ -372,6 +376,7 @@ void setup()
|
|||
trigger = triggerPri_GM7X;
|
||||
getRPM = getRPM_GM7X;
|
||||
getCrankAngle = getCrankAngle_GM7X;
|
||||
triggerSetEndTeeth = triggerSetEndTeeth_GM7X;
|
||||
|
||||
if(configPage2.TrigEdge == 0) { attachInterrupt(triggerInterrupt, trigger, RISING); } // Attach the crank trigger wheel interrupt (Hall sensor drags to ground when triggering)
|
||||
else { attachInterrupt(triggerInterrupt, trigger, FALLING); }
|
||||
|
@ -382,6 +387,7 @@ void setup()
|
|||
trigger = triggerPri_4G63;
|
||||
getRPM = getRPM_4G63;
|
||||
getCrankAngle = getCrankAngle_4G63;
|
||||
triggerSetEndTeeth = triggerSetEndTeeth_4G63;
|
||||
|
||||
//These may both need to change, not sure
|
||||
if(configPage2.TrigEdge == 0)
|
||||
|
@ -401,6 +407,7 @@ void setup()
|
|||
trigger = triggerPri_24X;
|
||||
getRPM = getRPM_24X;
|
||||
getCrankAngle = getCrankAngle_24X;
|
||||
triggerSetEndTeeth = triggerSetEndTeeth_24X;
|
||||
|
||||
if(configPage2.TrigEdge == 0) { attachInterrupt(triggerInterrupt, trigger, RISING); } // Attach the crank trigger wheel interrupt (Hall sensor drags to ground when triggering)
|
||||
else { attachInterrupt(triggerInterrupt, trigger, FALLING); } // Primary trigger connects to
|
||||
|
@ -412,6 +419,7 @@ void setup()
|
|||
trigger = triggerPri_Jeep2000;
|
||||
getRPM = getRPM_Jeep2000;
|
||||
getCrankAngle = getCrankAngle_Jeep2000;
|
||||
triggerSetEndTeeth = triggerSetEndTeeth_Jeep2000;
|
||||
|
||||
if(configPage2.TrigEdge == 0) { attachInterrupt(triggerInterrupt, trigger, RISING); } // Attach the crank trigger wheel interrupt (Hall sensor drags to ground when triggering)
|
||||
else { attachInterrupt(triggerInterrupt, trigger, FALLING); } // Primary trigger connects to
|
||||
|
@ -423,6 +431,7 @@ void setup()
|
|||
trigger = triggerPri_Audi135;
|
||||
getRPM = getRPM_Audi135;
|
||||
getCrankAngle = getCrankAngle_Audi135;
|
||||
triggerSetEndTeeth = triggerSetEndTeeth_Audi135;
|
||||
|
||||
if(configPage2.TrigEdge == 0) { attachInterrupt(triggerInterrupt, trigger, RISING); } // Attach the crank trigger wheel interrupt (Hall sensor drags to ground when triggering)
|
||||
else { attachInterrupt(triggerInterrupt, trigger, FALLING); }
|
||||
|
@ -434,6 +443,7 @@ void setup()
|
|||
trigger = triggerPri_HondaD17;
|
||||
getRPM = getRPM_HondaD17;
|
||||
getCrankAngle = getCrankAngle_HondaD17;
|
||||
triggerSetEndTeeth = triggerSetEndTeeth_HondaD17;
|
||||
|
||||
if(configPage2.TrigEdge == 0) { attachInterrupt(triggerInterrupt, trigger, RISING); } // Attach the crank trigger wheel interrupt (Hall sensor drags to ground when triggering)
|
||||
else { attachInterrupt(triggerInterrupt, trigger, FALLING); } // Primary trigger connects to
|
||||
|
@ -445,6 +455,7 @@ void setup()
|
|||
trigger = triggerPri_Miata9905;
|
||||
getRPM = getRPM_Miata9905;
|
||||
getCrankAngle = getCrankAngle_Miata9905;
|
||||
triggerSetEndTeeth = triggerSetEndTeeth_Miata9905;
|
||||
|
||||
//These may both need to change, not sure
|
||||
if(configPage2.TrigEdge == 0)
|
||||
|
@ -464,6 +475,7 @@ void setup()
|
|||
trigger = triggerPri_MazdaAU;
|
||||
getRPM = getRPM_MazdaAU;
|
||||
getCrankAngle = getCrankAngle_MazdaAU;
|
||||
triggerSetEndTeeth = triggerSetEndTeeth_MazdaAU;
|
||||
|
||||
if(configPage2.TrigEdge == 0) { attachInterrupt(triggerInterrupt, trigger, RISING); } // Attach the crank trigger wheel interrupt (Hall sensor drags to ground when triggering)
|
||||
else { attachInterrupt(triggerInterrupt, trigger, FALLING); } // Primary trigger connects to
|
||||
|
@ -475,6 +487,7 @@ void setup()
|
|||
trigger = triggerPri_DualWheel; //Is identical to the dual wheel decoder, so that is used. Same goes for the secondary below
|
||||
getRPM = getRPM_non360;
|
||||
getCrankAngle = getCrankAngle_non360;
|
||||
triggerSetEndTeeth = triggerSetEndTeeth_Non360;
|
||||
|
||||
if(configPage2.TrigEdge == 0) { attachInterrupt(triggerInterrupt, trigger, RISING); } // Attach the crank trigger wheel interrupt (Hall sensor drags to ground when triggering)
|
||||
else { attachInterrupt(triggerInterrupt, trigger, FALLING); }
|
||||
|
@ -486,6 +499,7 @@ void setup()
|
|||
trigger = triggerPri_Nissan360;
|
||||
getRPM = getRPM_Nissan360;
|
||||
getCrankAngle = getCrankAngle_Nissan360;
|
||||
triggerSetEndTeeth = triggerSetEndTeeth_Nissan360;
|
||||
|
||||
if(configPage2.TrigEdge == 0) { attachInterrupt(triggerInterrupt, trigger, RISING); } // Attach the crank trigger wheel interrupt (Hall sensor drags to ground when triggering)
|
||||
else { attachInterrupt(triggerInterrupt, trigger, FALLING); }
|
||||
|
@ -497,6 +511,7 @@ void setup()
|
|||
trigger = triggerPri_Subaru67;
|
||||
getRPM = getRPM_Subaru67;
|
||||
getCrankAngle = getCrankAngle_Subaru67;
|
||||
triggerSetEndTeeth = triggerSetEndTeeth_Subaru67;
|
||||
|
||||
if(configPage2.TrigEdge == 0) { attachInterrupt(triggerInterrupt, trigger, RISING); } // Attach the crank trigger wheel interrupt (Hall sensor drags to ground when triggering)
|
||||
else { attachInterrupt(triggerInterrupt, trigger, FALLING); }
|
||||
|
@ -508,6 +523,7 @@ void setup()
|
|||
trigger = triggerPri_Daihatsu;
|
||||
getRPM = getRPM_Daihatsu;
|
||||
getCrankAngle = getCrankAngle_Daihatsu;
|
||||
triggerSetEndTeeth = triggerSetEndTeeth_Daihatsu;
|
||||
|
||||
if(configPage2.TrigEdge == 0) { attachInterrupt(triggerInterrupt, trigger, RISING); } // Attach the crank trigger wheel interrupt (Hall sensor drags to ground when triggering)
|
||||
else { attachInterrupt(triggerInterrupt, trigger, FALLING); }
|
||||
|
@ -1276,7 +1292,8 @@ void loop()
|
|||
|
||||
//Calculate start angle for each channel
|
||||
//1 cylinder (Everyone gets this)
|
||||
ignition1StartAngle = CRANK_ANGLE_MAX_IGN - currentStatus.advance - dwellAngle; // 360 - desired advance angle - number of degrees the dwell will take
|
||||
ignition1EndAngle = CRANK_ANGLE_MAX_IGN - currentStatus.advance;
|
||||
ignition1StartAngle = ignition1EndAngle - dwellAngle; // 360 - desired advance angle - number of degrees the dwell will take
|
||||
if(ignition1StartAngle < 0) {ignition1StartAngle += CRANK_ANGLE_MAX_IGN;}
|
||||
|
||||
//This test for more cylinders and do the same thing
|
||||
|
@ -1284,40 +1301,50 @@ void loop()
|
|||
{
|
||||
//2 cylinders
|
||||
case 2:
|
||||
ignition2StartAngle = channel2IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance - dwellAngle;
|
||||
ignition2EndAngle = channel2IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance;
|
||||
ignition2StartAngle = ignition2EndAngle - dwellAngle;
|
||||
if(ignition2StartAngle > CRANK_ANGLE_MAX_IGN) {ignition2StartAngle -= CRANK_ANGLE_MAX_IGN;}
|
||||
break;
|
||||
//3 cylinders
|
||||
case 3:
|
||||
ignition2StartAngle = channel2IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance - dwellAngle;
|
||||
ignition2EndAngle = channel2IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance;
|
||||
ignition2StartAngle = ignition2EndAngle - dwellAngle;
|
||||
if(ignition2StartAngle > CRANK_ANGLE_MAX_IGN) {ignition2StartAngle -= CRANK_ANGLE_MAX_IGN;}
|
||||
ignition3EndAngle = channel3IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance;
|
||||
ignition3StartAngle = channel3IgnDegrees + 360 - currentStatus.advance - dwellAngle;
|
||||
if(ignition3StartAngle > CRANK_ANGLE_MAX_IGN) {ignition3StartAngle -= CRANK_ANGLE_MAX_IGN;}
|
||||
break;
|
||||
//4 cylinders
|
||||
case 4:
|
||||
ignition2StartAngle = channel2IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance - dwellAngle;
|
||||
ignition2EndAngle = channel2IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance;
|
||||
ignition2StartAngle = ignition2EndAngle - dwellAngle;
|
||||
if(ignition2StartAngle > CRANK_ANGLE_MAX_IGN) {ignition2StartAngle -= CRANK_ANGLE_MAX_IGN;}
|
||||
if(ignition2StartAngle < 0) {ignition2StartAngle += CRANK_ANGLE_MAX_IGN;}
|
||||
|
||||
if(configPage2.sparkMode == IGN_MODE_SEQUENTIAL)
|
||||
{
|
||||
ignition3StartAngle = channel3IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance - dwellAngle;
|
||||
ignition3EndAngle = channel3IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance;
|
||||
ignition3StartAngle = ignition3EndAngle - dwellAngle;
|
||||
if(ignition3StartAngle > CRANK_ANGLE_MAX_IGN) {ignition3StartAngle -= CRANK_ANGLE_MAX_IGN;}
|
||||
ignition4StartAngle = channel4IgnDegrees + CRANK_ANGLE_MAX - currentStatus.advance - dwellAngle;
|
||||
|
||||
ignition4EndAngle = channel4IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance;
|
||||
ignition4StartAngle = ignition4EndAngle - dwellAngle;
|
||||
if(ignition4StartAngle > CRANK_ANGLE_MAX_IGN) {ignition4StartAngle -= CRANK_ANGLE_MAX_IGN;}
|
||||
}
|
||||
break;
|
||||
//5 cylinders
|
||||
case 5:
|
||||
ignition2StartAngle = channel2IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance - dwellAngle;
|
||||
ignition2EndAngle = channel2IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance;
|
||||
ignition2StartAngle = ignition2EndAngle - dwellAngle;
|
||||
if(ignition2StartAngle > CRANK_ANGLE_MAX_IGN) {ignition2StartAngle -= CRANK_ANGLE_MAX_IGN;}
|
||||
if(ignition2StartAngle < 0) {ignition2StartAngle += CRANK_ANGLE_MAX_IGN;}
|
||||
|
||||
ignition3StartAngle = channel3IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance - dwellAngle;
|
||||
ignition3EndAngle = channel3IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance;
|
||||
ignition3StartAngle = ignition3EndAngle - dwellAngle;
|
||||
if(ignition3StartAngle > CRANK_ANGLE_MAX_IGN) {ignition3StartAngle -= CRANK_ANGLE_MAX_IGN;}
|
||||
|
||||
ignition4StartAngle = channel4IgnDegrees + CRANK_ANGLE_MAX - currentStatus.advance - dwellAngle;
|
||||
ignition4EndAngle = channel4IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance;
|
||||
ignition4StartAngle = ignition4EndAngle - dwellAngle;
|
||||
if(ignition4StartAngle > CRANK_ANGLE_MAX_IGN) {ignition4StartAngle -= CRANK_ANGLE_MAX_IGN;}
|
||||
|
||||
ignition5StartAngle = channel5IgnDegrees + CRANK_ANGLE_MAX - currentStatus.advance - dwellAngle;
|
||||
|
@ -1326,18 +1353,26 @@ void loop()
|
|||
break;
|
||||
//6 cylinders
|
||||
case 6:
|
||||
ignition2StartAngle = channel2IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance - dwellAngle;
|
||||
ignition2EndAngle = channel2IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance;
|
||||
ignition2StartAngle = ignition2EndAngle - dwellAngle;
|
||||
if(ignition2StartAngle > CRANK_ANGLE_MAX_IGN) {ignition2StartAngle -= CRANK_ANGLE_MAX_IGN;}
|
||||
ignition3StartAngle = channel3IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance - dwellAngle;
|
||||
|
||||
ignition3EndAngle = channel3IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance;
|
||||
ignition3StartAngle = ignition3EndAngle - dwellAngle;
|
||||
if(ignition3StartAngle > CRANK_ANGLE_MAX_IGN) {ignition3StartAngle -= CRANK_ANGLE_MAX_IGN;}
|
||||
break;
|
||||
//8 cylinders
|
||||
case 8:
|
||||
ignition2StartAngle = channel2IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance - dwellAngle;
|
||||
ignition2EndAngle = channel2IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance;
|
||||
ignition2StartAngle = ignition2EndAngle - dwellAngle;
|
||||
if(ignition2StartAngle > CRANK_ANGLE_MAX_IGN) {ignition2StartAngle -= CRANK_ANGLE_MAX_IGN;}
|
||||
ignition3StartAngle = channel3IgnDegrees + CRANK_ANGLE_MAX - currentStatus.advance - dwellAngle;
|
||||
|
||||
ignition3EndAngle = channel3IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance;
|
||||
ignition3StartAngle = ignition3EndAngle - dwellAngle;
|
||||
if(ignition3StartAngle > CRANK_ANGLE_MAX_IGN) {ignition3StartAngle -= CRANK_ANGLE_MAX_IGN;}
|
||||
ignition4StartAngle = channel4IgnDegrees + CRANK_ANGLE_MAX - currentStatus.advance - dwellAngle;
|
||||
|
||||
ignition4EndAngle = channel4IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance;
|
||||
ignition4StartAngle = ignition4EndAngle - dwellAngle;
|
||||
if(ignition4StartAngle > CRANK_ANGLE_MAX_IGN) {ignition4StartAngle -= CRANK_ANGLE_MAX_IGN;}
|
||||
break;
|
||||
|
||||
|
@ -1345,6 +1380,7 @@ void loop()
|
|||
default:
|
||||
break;
|
||||
}
|
||||
if(configPage1.perToothIgn == true) { triggerSetEndTeeth(); } //If ignition timing is being tracked per tooth, perform the calcs to get the end teeth
|
||||
|
||||
//***********************************************************************************************
|
||||
//| BEGIN FUEL SCHEDULES
|
||||
|
|
Loading…
Reference in New Issue