Merge pull request #35 from noisymime/master

08042017 update
This commit is contained in:
Autohome2 2017-04-09 01:22:13 +01:00 committed by GitHub
commit 7b42e12da4
26 changed files with 9191 additions and 85 deletions

View File

@ -1,7 +1,7 @@
<?xml version="1.0" encoding="ISO-8859-1"?>
<msq xmlns="http://www.msefi.com/:msq">
<bibliography author="TunerStudio MS(Beta) 3.0.18 - EFI Analytics, Inc." tuneComment="" writeDate="Fri Mar 03 12:50:33 AEDT 2017"/>
<versionInfo fileFormat="5.0" firmwareInfo="Speeduino+2017.02" nPages="10" signature="speeduino 201702"/>
<bibliography author="TunerStudio MS(Beta) 3.0.18.08 - EFI Analytics, Inc." tuneComment="" writeDate="Mon Apr 03 16:10:18 AEST 2017"/>
<versionInfo fileFormat="5.0" firmwareInfo="Speeduino+2017.03" nPages="10" signature="speeduino 201703"/>
<page>
<pcVariable name="tsCanId">"0"</pcVariable>
</page>
@ -140,16 +140,10 @@
<constant digits="0" name="flexFuelLow" units="%">100.0</constant>
<constant digits="0" name="flexFuelHigh" units="%">163.0</constant>
<constant digits="0" name="flexAdvLow" units="Deg">0.0</constant>
<constant digits="0" name="flexAdvHigh" units="Deg">85.0</constant>
<constant digits="0" name="flexAdvHigh" units="Deg">10.0</constant>
<constant digits="0" name="iacCLminDuty" units="%">0.0</constant>
<constant digits="0" name="iacCLmaxDuty" units="%">0.0</constant>
<constant digits="0" name="boostMinDuty" units="%">0.0</constant>
<constant digits="0" name="UNALLOCATED_SPACE_1_0" units="RAW">
0.0
</constant>
<constant digits="0" name="UNALLOCATED_TOP_1" units="RAW">
0.0
</constant>
</page>
<page number="2" size="288">
<constant cols="16" digits="0" name="advTable1" rows="16" units="deg">
@ -219,7 +213,7 @@
<constant name="TrigPattern">"Missing Tooth"</constant>
<constant name="TrigEdgeSec">"Leading"</constant>
<constant name="fuelPumpPin">"Board Default"</constant>
<constant name="unused4-6h">"No"</constant>
<constant name="useResync">"No"</constant>
<constant digits="0" name="unused4-7" units="ADC">0.0</constant>
<constant digits="0" name="IdleAdvRPM" units="RPM">3200.0</constant>
<constant digits="1" name="IdleAdvCLT" units="C">-21.0</constant>
@ -230,7 +224,7 @@
<constant name="sparkMode">"Wasted Spark"</constant>
<constant name="dfcoEnabled">"Off"</constant>
<constant name="TrigFilter">"Off"</constant>
<constant name="ignCranklock">"Off"</constant>
<constant name="ignCranklock">"On"</constant>
<constant digits="1" name="dwellcrank" units="ms">4.5</constant>
<constant digits="1" name="dwellrun" units="ms">3.0</constant>
<constant digits="0" name="numteeth" units="teeth">36.0</constant>

View File

@ -0,0 +1,43 @@
$fn=50;
height=1;
hole_radius=(3.3782/2)+0.5;
corner_radius=4.00;
//hole_radius=(3.3782/1);
module plate()
{
difference()
{
//Basic outline
minkowski() {
cube([95.02,45,height]);
// rounded corners
cylinder(r=corner_radius,h=height);
}
//Holes
translate([0,0,-5]) cylinder(r=hole_radius, h=10);
translate([0,45,-5]) cylinder(r=hole_radius, h=10);
translate([95.02,0,-5]) cylinder(r=hole_radius, h=10);
translate([95.02,45,-5]) cylinder(r=hole_radius, h=10);
//USB cutout
USB_height = 11;
translate([-corner_radius+29.3,-corner_radius+13,-5]) cube([14,USB_height,10]);
//MAP cutout
//translate([20,110,screw_window_z+screw_window_height/2-2]) rotate ([90,0,0]) cylinder(r=3,h=screw_window_height);
translate([-corner_radius+90,-corner_radius+15,-5]) cylinder(r=3,h=10);
//Main loom cutout
loom_width=84;
loom_height=20;
translate([-corner_radius+9,-corner_radius+29.2,-5]) cube([84,20,10]);
} //difference()
}
//projection(cut = true) plate(); //2D projection
plate(); //3D model

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,15 @@
Part/Designator,Manufacture Part Number
R3,RC0805FR-071KL
R5,RC0805FR-071KL
R4,RC0805JR-0710KL
R6,RC0805JR-0710KL
R7,RC0805JR-0710KL
R9,RC0805JR-0710KL
R11,RC0805JR-0710KL
R13,RC0805JR-0710KL
MAX9926,MAX9926UAEE+T
C2,CC0805KRX7R9BB103
C3,CC0805KKX7R7BB105
C4,CC0805KRX7R9BB102
C5,CC0805KRX7R9BB102
C1,CC0805ZRY5V9BB104
1 Part/Designator Manufacture Part Number
2 R3 RC0805FR-071KL
3 R5 RC0805FR-071KL
4 R4 RC0805JR-0710KL
5 R6 RC0805JR-0710KL
6 R7 RC0805JR-0710KL
7 R9 RC0805JR-0710KL
8 R11 RC0805JR-0710KL
9 R13 RC0805JR-0710KL
10 MAX9926 MAX9926UAEE+T
11 C2 CC0805KRX7R9BB103
12 C3 CC0805KKX7R7BB105
13 C4 CC0805KRX7R9BB102
14 C5 CC0805KRX7R9BB102
15 C1 CC0805ZRY5V9BB104

View File

@ -0,0 +1,8 @@
Part/Designator,Manufacture Part Number,Quantity
"R3,R5",RC0805FR-071KL,2
"R4,R6,R7,R9,R11,R13",RC0805JR-0710KL,6
MAX9926,MAX9926UAEE+T,1
C2,CC0805KRX7R9BB103,1
C3,CC0805KKX7R7BB105,1
"C4,C5",CC0805KRX7R9BB102,2
C1,CC0805ZRY5V9BB104,1
1 Part/Designator Manufacture Part Number Quantity
2 R3,R5 RC0805FR-071KL 2
3 R4,R6,R7,R9,R11,R13 RC0805JR-0710KL 6
4 MAX9926 MAX9926UAEE+T 1
5 C2 CC0805KRX7R9BB103 1
6 C3 CC0805KKX7R7BB105 1
7 C4,C5 CC0805KRX7R9BB102 2
8 C1 CC0805ZRY5V9BB104 1

Binary file not shown.

Before

Width:  |  Height:  |  Size: 1.5 MiB

After

Width:  |  Height:  |  Size: 1.5 MiB

View File

@ -0,0 +1 @@
Part/Designator,Manufacture Part Number,Quantity C16,T356G106K035AT,1 "C1,C3,C5,C7,C9,C13,C15",C322C104M5R5TA7301,7 C14,T356F476K006AT,1 C18,AR215F334K4R,1 C19,C317C103K5R5TA,1 "C11,C12,C20",CC0805KKX7R7BB105,3 C23,C317C472K1R5TA,1 "C2,C4,C6,C8,C24,C10",CL21B224KOCNNNC,6 ,, D16,1N5919BG,1 "D15,D17",1N5818-TP,2 "LED1,LED2,LED3,LED4,LED5,LED6,LED7,LED8",LTL-4221N,8 "D9,D10,D11,D12",1N4004-TP,4 ,, U2,ERZ-V14D220,1 ,, Jumpers for male pins,969102-0000-DA,5 "JP1,JP2,JP3",M20-9990345,3 "JP4,JP5",M20-9990245,2 J4,3020-40-0100-00,1 IC3,PPPC041LFBN-RC,2 ,, "Q1,Q2,Q3,Q4,Q5,Q6,Q7,Q8",STP62NS04Z,8 ,, R54,MFR-25FBF52-10K,1 "R10,R13,R16,R19,R23,R24,R29,R30,R39,R40,R50,R51,R57,R58",MFR-25FBF52-1K,14 "R9,R12,R15,R18,R26,R28,R33,R34",MFR-25FBF52-680,8 "R2,R4,R6,R8,R22,R41",CFM14JT470R,6 "R1,R3,R61",RT0805BRD072K49L,3 R7,RC0805FR-073K9L,1 R21,MFP-25BRD52-1K,1 "R11,R14,R17,R20,R35,R36,R37,R38,R48,R49,R55,R56",MFR-25FBF52-100K,12 "R25,R27,R31,R32",FMP200JR-52-180R,4 "R59,R60",RC0805FR-071KL,2 ,, U1,LM2940T-5.0/NOPB,1 MPX4250A,MPX4250AP,1 "IC1,IC2",TC4424EPA,2 IC4,SP721APP,1 ,,3
Can't render this file because it contains an unexpected character in line 1 and column 71.

Binary file not shown.

View File

@ -7,7 +7,7 @@
queryCommand = "Q"
;signature = 20
signature = "speeduino 201703-dev"
signature = "speeduino 201703"
versionInfo = "S" ; Put this in the title bar.
@ -255,7 +255,7 @@ page = 4
TrigSpeed = bits, U08, 5,[1:1], "Crank Speed", "Cam Speed"
IgInv = bits, U08, 5,[2:2], "Going Low", "Going High"
oddfire = bits, U08, 5,[3:3], "No", "Yes"
TrigPattern= bits, U08, 5,[4:7], "Missing Tooth", "Basic Distributor", "Dual Wheel", "GM 7X", "4G63 / Miata", "GM 24X", "Jeep 2000", "Audi 135", "Honda D17", "Miata 99-05", "Mazda AU", "Non-360 Dual", "Nissan 360", "INVALID", "INVALID", "INVALID"
TrigPattern= bits, U08, 5,[4:7], "Missing Tooth", "Basic Distributor", "Dual Wheel", "GM 7X", "4G63 / Miata", "GM 24X", "Jeep 2000", "Audi 135", "Honda D17", "Miata 99-05", "Mazda AU", "Non-360 Dual", "Nissan 360", "Subaru 6/7", "INVALID", "INVALID"
TrigEdgeSec= bits, U08, 6,[0:0], "Leading", "Trailing"
fuelPumpPin= bits , U08, 6,[1:6], "Board Default", "INVALID", "INVALID", "3", "4", "5", "6", "7", "8", "9", "10", "11", "12", "13", "14", "15", "16", "17", "18", "19", "20", "21", "22", "23", "24", "25", "26", "27", "28", "29", "30", "31", "32", "33", "34", "35", "36", "37", "38", "39", "40", "41", "42", "43", "44", "45", "46", "47", "48", "49", "50", "51", "52", "53", "54", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID", "INVALID"
useResync = bits, U08, 6,[7:7], "No", "Yes"
@ -437,7 +437,7 @@ page = 7
#endif
iacAlgorithm = bits , U08, 52, [0:2], "None", "On/Off", "PWM Open loop", "PWM Closed loop", "Stepper Open Loop", "Stepper Closed Loop", "INVALID", "INVALID"
iacStepTime = bits , U08, 52, [3:5], "1", "2", "3", "4", "5", "6"
iacStepTime = bits , U08, 52, [3:5], "INVALID","1", "2", "3", "4", "5", "6","INVALID"
iacChannels = bits, U08, 52, [6:6], "1", "2"
iacPWMdir = bits , U08, 52, [7:7], "Normal", "Reverse"
@ -881,6 +881,7 @@ menuDialog = main
iacPWMdir = "Normal PWM valves increase RPM with higher duty. If RPM decreases with higher duty then select Reverse"
iacCLminDuty= "When using closed loop idle control, this is the minimum duty cycle that the PID loop will allow. Combined with the maximum value, this specifies the working range of your idle valve"
iacCLmaxDuty= "When using closed loop idle control, this is the maximum duty cycle that the PID loop will allow. Combined with the minimum value, this specifies the working range of your idle valve"
iacFastTemp = "Below this temperature, the idle output will be high (On). Above this temperature, it will turn off."
oddfire2 = "The ATDC angle of channel 2 for oddfire engines. This is relative to the TDC angle of channel 1"
oddfire3 = "The ATDC angle of channel 3 for oddfire engines. This is relative to the TDC angle of channel 1 (NOT channel 2)"
@ -1249,6 +1250,7 @@ menuDialog = main
settingOption = "MPXH6400", mapMin=3, mapMax=416
settingOption = "MPX4400", mapMin=0, mapMax=400
settingOption = "Denso 079800", mapMin=0, mapMax=173 ; http://speeduino.com/forum/viewtopic.php?f=18&t=510&p=7023#p7021
settingOption = "VW/Audi/Porsche 250kPa", mapMin=26, mapMax=250 ; http://speeduino.com/forum/viewtopic.php?p=17502#p17502
dialog = boostSettings, "Boost Control"
field = "Boost Control Enabled", boostEnabled

Binary file not shown.

Before

Width:  |  Height:  |  Size: 46 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 59 KiB

View File

Before

Width:  |  Height:  |  Size: 16 KiB

After

Width:  |  Height:  |  Size: 16 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 31 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 25 KiB

After

Width:  |  Height:  |  Size: 26 KiB

View File

@ -72,12 +72,12 @@ void command()
break;
case 'S': // send code version
Serial.print("Speeduino 2017.03-dev");
Serial.print("Speeduino 2017.03");
currentStatus.secl = 0; //This is required in TS3 due to its stricter timings
break;
case 'Q': // send code version
Serial.print("speeduino 201703-dev");
Serial.print("speeduino 201703");
break;
case 'V': // send VE table and constants in binary

View File

@ -46,6 +46,7 @@ A common function is simpler
static inline int stdGetRPM()
{
if( !currentStatus.hasSync ) { return 0; } //Safety check
if( BIT_CHECK(currentStatus.engine, BIT_ENGINE_CRANK) && currentStatus.startRevolutions == 0) { return 0; } //Prevents crazy RPM spike when there has been less than 1 full revolution
noInterrupts();
revolutionTime = (toothOneTime - toothOneMinusOneTime); //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)
interrupts();
@ -914,7 +915,8 @@ void triggerSec_Audi135()
currentStatus.hasSync = true;
toothSystemCount = 3; //Need to set this to 3 so that the next primary tooth is counted
}
else if (configPage2.useResync) { toothCurrentCount = 0; }
else if (configPage2.useResync) { toothCurrentCount = 0; toothSystemCount = 3; }
else if ( currentStatus.startRevolutions < 100 && toothCurrentCount != 45 ) { toothCurrentCount = 0; }
revolutionOne = 1; //Sequential revolution reset
}
@ -1529,3 +1531,139 @@ int getCrankAngle_Nissan360(int timePerDegree)
}
return (toothCurrentCount * triggerToothAngle);
}
/* -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
Name: Nissan 360 tooth with cam
Desc:
Note:
*/
void triggerSetup_Subaru67()
{
triggerFilterTime = (1000000 / (MAX_RPM / 60 * 360UL)); //Trigger filter time is the shortest possible time (in uS) that there can be between crank teeth (ie at max RPM). Any pulses that occur faster than this time will be disgarded as noise
triggerSecFilterTime = (int)(1000000 / (MAX_RPM / 60 * 2)) / 2; //Same as above, but fixed at 2 teeth on the secondary input and divided by 2 (for cam speed)
secondaryToothCount = 0; //Initially set to 0 prior to calculating the secondary window duration
secondDerivEnabled = false;
decoderIsSequential = true;
toothCurrentCount = 1;
triggerToothAngle = 2;
MAX_STALL_TIME = (3333UL * 93); //Minimum 50rpm. (3333uS is the time per degree at 50rpm)
toothAngles[0] = 710; //tooth #1
toothAngles[1] = 83; //tooth #2
toothAngles[2] = 115; //tooth #3
toothAngles[3] = 170; //tooth #4
toothAngles[4] = toothAngles[1] + 180;
toothAngles[5] = toothAngles[2] + 180;
toothAngles[6] = toothAngles[3] + 180;
toothAngles[7] = toothAngles[1] + 360;
toothAngles[8] = toothAngles[2] + 360;
toothAngles[9] = toothAngles[3] + 360;
toothAngles[10] = toothAngles[1] + 540;
toothAngles[11] = toothAngles[2] + 540;
}
void triggerPri_Subaru67()
{
curTime = micros();
//curGap = curTime - toothLastToothTime;
//if ( curGap < triggerFilterTime ) { return; } //Pulses should never be less than triggerFilterTime, so if they are it means a false trigger.
toothCurrentCount++; //Increment the tooth counter
addToothLogEntry(curGap);
toothLastMinusOneToothTime = toothLastToothTime;
toothLastToothTime = curTime;
if ( !currentStatus.hasSync || configPage2.useResync)
{
//Sync is determined by counting the number of cam teeth that have passed between the crank teeth
switch(secondaryToothCount)
{
case 0:
//If no teeth have passed, we can't do anything
break;
case 1:
//Can't do anything with a single pulse from the cam either (We need either 2 or 3 pulses)
secondaryToothCount = 0;
break;
case 2:
toothCurrentCount = 8;
currentStatus.hasSync = true;
secondaryToothCount = 0;
break;
case 3:
toothCurrentCount = 2;
currentStatus.hasSync = true;
secondaryToothCount = 0;
break;
default:
//Almost certainly due to noise
break;
}
}
if ( !currentStatus.hasSync ) { return; } //Check again if we have sync and return if not
//Locked timing during cranking. This is fixed at 10* BTDC.
if ( BIT_CHECK(currentStatus.engine, BIT_ENGINE_CRANK) && configPage2.ignCranklock)
{
if( toothCurrentCount == 1 || toothCurrentCount == 7 ) { endCoil1Charge(); endCoil3Charge(); }
else if( toothCurrentCount == 4 || toothCurrentCount == 10 ) { endCoil2Charge(); endCoil4Charge(); }
}
if ( toothCurrentCount > 12 ) //2 complete crank revolutions
{
toothCurrentCount = 1;
toothOneMinusOneTime = toothOneTime;
toothOneTime = curTime;
currentStatus.startRevolutions++; //Counter
}
//setFilter(curGap); //Recalc the new filter value
}
void triggerSec_Subaru67()
{
curTime2 = micros();
curGap2 = curTime2 - toothLastSecToothTime;
//if ( curGap2 < triggerSecFilterTime ) { return; }
toothLastSecToothTime = curTime2;
//triggerSecFilterTime = curGap2 >> 2; //Set filter at 25% of the current speed
secondaryToothCount++;
}
int getRPM_Subaru67()
{
//if(currentStatus.RPM < configPage2.crankRPM) { return crankingGetRPM(configPage2.triggerTeeth); }
return stdGetRPM();
}
int getCrankAngle_Subaru67(int timePerDegree)
{
if(!currentStatus.hasSync) { return 0; }
//This is the current angle ATDC the engine is at. This is the last known position based on what tooth was last 'seen'. It is only accurate to the resolution of the trigger wheel (Eg 36-1 is 10 degrees)
unsigned long tempToothLastToothTime;
int tempToothCurrentCount;
//Grab some variables that are used in the trigger code and assign them to temp variables.
noInterrupts();
tempToothCurrentCount = toothCurrentCount;
tempToothLastToothTime = toothLastToothTime;
interrupts();
int crankAngle = toothAngles[(tempToothCurrentCount - 1)] + configPage2.triggerAngle; //Perform a lookup of the fixed toothAngles array to find what the angle of the last tooth passed was.
//Estimate the number of degrees travelled since the last tooth}
unsigned long elapsedTime = micros() - tempToothLastToothTime;
if(elapsedTime < SHRT_MAX ) { crankAngle += div((int)elapsedTime, timePerDegree).quot; } //This option is much faster, but only available for smaller values of elapsedTime
else { crankAngle += ldiv(elapsedTime, timePerDegree).quot; }
if (crankAngle >= 720) { crankAngle -= 720; }
if (crankAngle > CRANK_ANGLE_MAX) { crankAngle -= CRANK_ANGLE_MAX; }
if (crankAngle < 0) { crankAngle += 360; }
return crankAngle;
}

View File

@ -264,10 +264,10 @@ struct config1 {
byte unused26 : 4;
byte indInjAng : 1;
byte injOpen; //Injector opening time (ms * 10)
unsigned int inj1Ang;
unsigned int inj2Ang;
unsigned int inj3Ang;
unsigned int inj4Ang;
uint16_t inj1Ang;
uint16_t inj2Ang;
uint16_t inj3Ang;
uint16_t inj4Ang;
//config1 in ini
byte mapSample : 2;
@ -299,12 +299,12 @@ struct config1 {
byte tpsMin;
byte tpsMax;
byte mapMin;
unsigned int mapMax;
uint16_t mapMax;
byte fpPrime; //Time (In seconds) that the fuel pump should be primed for on power up
byte stoich;
unsigned int oddfire2; //The ATDC angle of channel 2 for oddfire
unsigned int oddfire3; //The ATDC angle of channel 3 for oddfire
unsigned int oddfire4; //The ATDC angle of channel 4 for oddfire
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)
@ -321,7 +321,7 @@ struct config1 {
//This mostly covers off variables that are required for ignition
struct config2 {
int triggerAngle;
int16_t triggerAngle;
byte FixAng;
byte CrankAng;
byte TrigAngMul; //Multiplier for non evenly divisible tooth counts.
@ -659,6 +659,7 @@ byte pinVVt_2; // vvt output 2
byte pinFan; // Cooling fan output
byte pinStepperDir; //Direction pin for the stepper motor driver
byte pinStepperStep; //Step pin for the stepper motor driver
byte pinStepperEnable; //Turning the DRV8825 driver on/off
byte pinLaunch;
byte pinIgnBypass; //The pin used for an ignition bypass (Optional)
byte pinFlex; //Pin with the flex sensor attached

View File

@ -87,9 +87,10 @@ void initialiseIdle()
case IAC_ALGORITHM_ONOFF:
//Case 1 is on/off idle control
if (currentStatus.coolant < configPage4.iacFastTemp)
if ((currentStatus.coolant + CALIBRATION_TEMPERATURE_OFFSET) < configPage4.iacFastTemp)
{
digitalWrite(pinIdle1, HIGH);
idleOn = true;
}
break;
@ -255,6 +256,7 @@ void idleControl()
{
//Only do a lookup of the required value around 4 times per second. Any more than this can create too much jitter and require a hyster value that is too high
idleStepper.targetIdleStep = table2D_getValue(&iacStepTable, (currentStatus.coolant + CALIBRATION_TEMPERATURE_OFFSET)) * 3; //All temps are offset by 40 degrees. Step counts are divided by 3 in TS. Multiply back out here
iacStepTime = configPage4.iacStepTime * 1000;
}
doStep();
}
@ -265,8 +267,12 @@ void idleControl()
//First thing to check is whether there is currently a step going on and if so, whether it needs to be turned off
if( checkForStepping() ) { return; } //If this is true it means there's either a step taking place or
if( !isStepperHomed() ) { return; } //Check whether homing is completed yet.
if( (idleCounter & 31) == 1) { idlePID.SetTunings(configPage3.idleKP, configPage3.idleKI, configPage3.idleKD); } //This only needs to be run very infrequently, once every 32 calls to idleControl(). This is approx. once per second
if( (idleCounter & 31) == 1)
{
//This only needs to be run very infrequently, once every 32 calls to idleControl(). This is approx. once per second
idlePID.SetTunings(configPage3.idleKP, configPage3.idleKI, configPage3.idleKD);
iacStepTime = configPage4.iacStepTime * 1000;
}
idle_cl_target_rpm = table2D_getValue(&iacClosedLoopTable, currentStatus.coolant + CALIBRATION_TEMPERATURE_OFFSET) * 10; //All temps are offset by 40 degrees
idlePID.Compute();
@ -322,8 +328,9 @@ static inline byte checkForStepping()
}
else
{
//Means we're in COOLING status but have been in this state long enough to
//Means we're in COOLING status but have been in this state long enough. Go into off state
idleStepper.stepperStatus = SOFF;
digitalWrite(pinStepperEnable, HIGH); //Disable the DRV8825
}
}
else
@ -344,6 +351,7 @@ static inline void doStep()
else if(idleStepper.targetIdleStep < idleStepper.curIdleStep) { digitalWrite(pinStepperDir, STEPPER_BACKWARD); idleStepper.curIdleStep--; }//Sets stepper direction to backwards
else if (idleStepper.targetIdleStep > idleStepper.curIdleStep) { digitalWrite(pinStepperDir, STEPPER_FORWARD); idleStepper.curIdleStep++; }//Sets stepper direction to forwards
digitalWrite(pinStepperEnable, LOW); //Enable the DRV8825
digitalWrite(pinStepperStep, HIGH);
idleStepper.stepStartTime = micros();
idleStepper.stepperStatus = STEPPING;
@ -360,10 +368,15 @@ static inline void disableIdle()
}
else if (configPage4.iacAlgorithm == IAC_ALGORITHM_STEP_CL || configPage4.iacAlgorithm == IAC_ALGORITHM_STEP_OL)
{
digitalWrite(pinStepperEnable, HIGH); //Disable the DRV8825
idleStepper.targetIdleStep = idleStepper.curIdleStep; //Don't try to move anymore
//The below appears to be causing issues, so for now this will simply halt the stepper entirely rather than taking it back to step 1
/*
idleStepper.targetIdleStep = 1; //Home the stepper
if( checkForStepping() ) { return; } //If this is true it means there's either a step taking place or
if( !isStepperHomed() ) { return; } //Check whether homing is completed yet.
doStep();
*/
}
}

View File

@ -77,6 +77,8 @@ See page 136 of the processors datasheet: http://www.atmel.com/Images/doc2549.pd
#define MAX_TIMER_PERIOD 262140 //The longest period of time (in uS) that the timer can permit (IN this case it is 65535 * 4, as each timer tick is 4uS)
#define uS_TO_TIMER_COMPARE(uS1) (uS1 >> 2) //Converts a given number of uS into the required number of timer ticks until that time has passed
//This is a hack until I make all the AVR timers run at the same speed
#define uS_TO_TIMER_COMPARE_SLOW(uS1) (uS1 >> 4)
#elif defined(CORE_TEENSY)
//http://shawnhymel.com/661/learning-the-teensy-lc-interrupt-service-routines/
@ -154,6 +156,8 @@ See page 136 of the processors datasheet: http://www.atmel.com/Images/doc2549.pd
#define MAX_TIMER_PERIOD 139808 // 2.13333333uS * 65535
#define uS_TO_TIMER_COMPARE(uS) ((uS * 15) >> 5) //Converts a given number of uS into the required number of timer ticks until that time has passed.
//Hack compatibility with AVR timers that run at different speeds
#define uS_TO_TIMER_COMPARE_SLOW(uS) ((uS * 15) >> 5)
#elif defined(STM32_MCU_SERIES)
//Placeholders ONLY!
@ -161,6 +165,7 @@ See page 136 of the processors datasheet: http://www.atmel.com/Images/doc2549.pd
//https://github.com/rogerclarkmelbourne/Arduino_STM32/blob/master/STM32F4/cores/maple/libmaple/timer.h#L51
#define MAX_TIMER_PERIOD 139808 // 2.13333333uS * 65535
#define uS_TO_TIMER_COMPARE(uS) ((uS * 15) >> 5) //Converts a given number of uS into the required number of timer ticks until that time has passed.
#define uS_TO_TIMER_COMPARE_SLOW(uS) ((uS * 15) >> 5) //Converts a given number of uS into the required number of timer ticks until that time has passed.
#define FUEL1_COUNTER (TIMER2->regs).gen->CNT
#define FUEL2_COUNTER (TIMER2->regs).gen->CNT

View File

@ -159,6 +159,11 @@ void initialiseSchedulers()
NVIC_ENABLE_IRQ(IRQ_FTM0);
NVIC_ENABLE_IRQ(IRQ_FTM1);
#elif defined(CORE_STM32)
(TIMER2->regs).gen->CCMR1 &= ~TIM_CCMR1_OC1M; //Select channel 1 output Compare and Mode
TIM3->CR1 |= TIM_CR1_CEN
#endif
fuelSchedule1.Status = OFF;
@ -211,8 +216,8 @@ void setFuelSchedule1(void (*startCallback)(), unsigned long timeout, unsigned l
* unsigned int absoluteTimeout = TCNT3 + (timeout / 16); //Each tick occurs every 16uS with the 256 prescaler, so divide the timeout by 16 to get ther required number of ticks. Add this to the current tick count to get the target time. This will automatically overflow as required
*/
noInterrupts();
fuelSchedule1.startCompare = FUEL1_COUNTER + (timeout >> 4); //As above, but with bit shift instead of / 16
fuelSchedule1.endCompare = fuelSchedule1.startCompare + (duration >> 4);
fuelSchedule1.startCompare = FUEL1_COUNTER + uS_TO_TIMER_COMPARE_SLOW(timeout);
fuelSchedule1.endCompare = fuelSchedule1.startCompare + uS_TO_TIMER_COMPARE_SLOW(duration);
fuelSchedule1.Status = PENDING; //Turn this schedule on
fuelSchedule1.schedulesSet++; //Increment the number of times this schedule has been set
/*if(channel5InjEnabled) { FUEL1_COMPARE = setQueue(timer3Aqueue, &fuelSchedule1, &fuelSchedule5, FUEL1_COUNTER); } //Schedule 1 shares a timer with schedule 5
@ -236,8 +241,8 @@ void setFuelSchedule2(void (*startCallback)(), unsigned long timeout, unsigned l
* unsigned int absoluteTimeout = TCNT3 + (timeout / 16); //Each tick occurs every 16uS with the 256 prescaler, so divide the timeout by 16 to get ther required number of ticks. Add this to the current tick count to get the target time. This will automatically overflow as required
*/
noInterrupts();
fuelSchedule2.startCompare = FUEL2_COUNTER + (timeout >> 4); //As above, but with bit shift instead of / 16
fuelSchedule2.endCompare = fuelSchedule2.startCompare + (duration >> 4);
fuelSchedule2.startCompare = FUEL2_COUNTER + uS_TO_TIMER_COMPARE_SLOW(timeout);
fuelSchedule2.endCompare = fuelSchedule2.startCompare + uS_TO_TIMER_COMPARE_SLOW(duration);
FUEL2_COMPARE = fuelSchedule2.startCompare; //Use the B copmare unit of timer 3
fuelSchedule2.Status = PENDING; //Turn this schedule on
fuelSchedule2.schedulesSet++; //Increment the number of times this schedule has been set
@ -259,8 +264,8 @@ void setFuelSchedule3(void (*startCallback)(), unsigned long timeout, unsigned l
* unsigned int absoluteTimeout = TCNT3 + (timeout / 16); //Each tick occurs every 16uS with the 256 prescaler, so divide the timeout by 16 to get ther required number of ticks. Add this to the current tick count to get the target time. This will automatically overflow as required
*/
noInterrupts();
fuelSchedule3.startCompare = FUEL3_COUNTER + (timeout >> 4); //As above, but with bit shift instead of / 16
fuelSchedule3.endCompare = fuelSchedule3.startCompare + (duration >> 4);
fuelSchedule3.startCompare = FUEL3_COUNTER + uS_TO_TIMER_COMPARE_SLOW(timeout);
fuelSchedule3.endCompare = fuelSchedule3.startCompare + uS_TO_TIMER_COMPARE_SLOW(duration);
FUEL3_COMPARE = fuelSchedule3.startCompare; //Use the C copmare unit of timer 3
fuelSchedule3.Status = PENDING; //Turn this schedule on
fuelSchedule3.schedulesSet++; //Increment the number of times this schedule has been set
@ -282,8 +287,8 @@ void setFuelSchedule4(void (*startCallback)(), unsigned long timeout, unsigned l
* unsigned int absoluteTimeout = TCNT3 + (timeout / 16); //Each tick occurs every 16uS with the 256 prescaler, so divide the timeout by 16 to get ther required number of ticks. Add this to the current tick count to get the target time. This will automatically overflow as required
*/
noInterrupts();
fuelSchedule4.startCompare = FUEL4_COUNTER + (timeout >> 4);
fuelSchedule4.endCompare = fuelSchedule4.startCompare + (duration >> 4);
fuelSchedule4.startCompare = FUEL4_COUNTER + uS_TO_TIMER_COMPARE_SLOW(timeout);
fuelSchedule4.endCompare = fuelSchedule4.startCompare + uS_TO_TIMER_COMPARE_SLOW(duration);
FUEL4_COMPARE = fuelSchedule4.startCompare; //Use the C copmare unit of timer 3
fuelSchedule4.Status = PENDING; //Turn this schedule on
fuelSchedule4.schedulesSet++; //Increment the number of times this schedule has been set
@ -390,8 +395,8 @@ void setIgnitionSchedule4(void (*startCallback)(), unsigned long timeout, unsign
if (timeout > MAX_TIMER_PERIOD) { timeout = MAX_TIMER_PERIOD - 1; } // If the timeout is >4x (Each tick represents 4uS) the maximum allowed value of unsigned int (65535), the timer compare value will overflow when appliedcausing erratic behaviour such as erroneous sparking.
noInterrupts();
ignitionSchedule4.startCompare = IGN4_COUNTER + (timeout >> 4); //As there is a tick every 4uS, there are timeout/4 ticks until the interrupt should be triggered ( >>2 divides by 4)
ignitionSchedule4.endCompare = ignitionSchedule4.startCompare + (duration >> 4);
ignitionSchedule4.startCompare = IGN4_COUNTER + uS_TO_TIMER_COMPARE_SLOW(timeout);
ignitionSchedule4.endCompare = ignitionSchedule4.startCompare + uS_TO_TIMER_COMPARE_SLOW(duration);
IGN4_COMPARE = ignitionSchedule4.startCompare;
ignitionSchedule4.Status = PENDING; //Turn this schedule on
ignitionSchedule4.schedulesSet++;
@ -412,8 +417,8 @@ void setIgnitionSchedule5(void (*startCallback)(), unsigned long timeout, unsign
if (timeout > MAX_TIMER_PERIOD) { timeout = MAX_TIMER_PERIOD - 1; } // If the timeout is >4x (Each tick represents 4uS) the maximum allowed value of unsigned int (65535), the timer compare value will overflow when appliedcausing erratic behaviour such as erroneous sparking.
noInterrupts();
ignitionSchedule5.startCompare = IGN5_COUNTER + (timeout >> 4); //As there is a tick every 4uS, there are timeout/4 ticks until the interrupt should be triggered ( >>2 divides by 4)
ignitionSchedule5.endCompare = ignitionSchedule5.startCompare + (duration >> 4);
ignitionSchedule5.startCompare = IGN5_COUNTER + uS_TO_TIMER_COMPARE_SLOW(timeout);
ignitionSchedule5.endCompare = ignitionSchedule5.startCompare + uS_TO_TIMER_COMPARE_SLOW(duration);
IGN5_COMPARE = ignitionSchedule5.startCompare;
ignitionSchedule5.Status = PENDING; //Turn this schedule on
ignitionSchedule5.schedulesSet++;

View File

@ -259,38 +259,45 @@ void setup()
currentStatus.launchingHard = false;
triggerFilterTime = 0; //Trigger filter time is the shortest possible time (in uS) that there can be between crank teeth (ie at max RPM). Any pulses that occur faster than this time will be disgarded as noise. This is simply a default value, the actual values are set in the setup() functinos of each decoder
switch (pinTrigger) {
//Arduino Mega 2560 mapping
case 2:
triggerInterrupt = 0; break;
case 3:
triggerInterrupt = 1; break;
case 18:
triggerInterrupt = 5; break;
case 19:
triggerInterrupt = 4; break;
case 20:
triggerInterrupt = 3; break;
case 21:
triggerInterrupt = 2; break;
#if defined(CORE_AVR)
switch (pinTrigger) {
//Arduino Mega 2560 mapping
case 2:
triggerInterrupt = 0; break;
case 3:
triggerInterrupt = 1; break;
case 18:
triggerInterrupt = 5; break;
case 19:
triggerInterrupt = 4; break;
case 20:
triggerInterrupt = 3; break;
case 21:
triggerInterrupt = 2; break;
}
#else
triggerInterrupt = pinTrigger;
#endif
}
switch (pinTrigger2) {
//Arduino Mega 2560 mapping
case 2:
triggerInterrupt2 = 0; break;
case 3:
triggerInterrupt2 = 1; break;
case 18:
triggerInterrupt2 = 5; break;
case 19:
triggerInterrupt2 = 4; break;
case 20:
triggerInterrupt2 = 3; break;
case 21:
triggerInterrupt2 = 2; break;
}
#if defined(CORE_AVR)
switch (pinTrigger2) {
//Arduino Mega 2560 mapping
case 2:
triggerInterrupt2 = 0; break;
case 3:
triggerInterrupt2 = 1; break;
case 18:
triggerInterrupt2 = 5; break;
case 19:
triggerInterrupt2 = 4; break;
case 20:
triggerInterrupt2 = 3; break;
case 21:
triggerInterrupt2 = 2; break;
}
#else
triggerInterrupt2 = pinTrigger2;
#endif
pinMode(pinTrigger, INPUT);
pinMode(pinTrigger2, INPUT);
pinMode(pinTrigger3, INPUT);
@ -462,6 +469,17 @@ void setup()
attachInterrupt(triggerInterrupt2, triggerSec_Nissan360, CHANGE);
break;
case 13:
triggerSetup_Subaru67();
trigger = triggerPri_Subaru67;
getRPM = getRPM_Subaru67;
getCrankAngle = getCrankAngle_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); }
attachInterrupt(triggerInterrupt2, triggerSec_Subaru67, FALLING);
break;
default:
trigger = triggerPri_missingTooth;
getRPM = getRPM_missingTooth;

View File

@ -13,15 +13,15 @@ The 2D table can contain either 8-bit (byte) or 16-bit (int) values
The valueSize variable should be set to either 8 or 16 to indicate this BEFORE the table is used
*/
struct table2D {
byte valueSize;
byte valueSize;
byte xSize;
byte *values;
byte *axisX;
int *values16;
int *axisX16;
int16_t *values16;
int16_t *axisX16;
//Store the last X and Y coordinates in the table. This is used to make the next check faster
int lastXMax, lastXMin;
};
@ -29,16 +29,16 @@ struct table2D {
void table2D_setSize(struct table2D targetTable, byte newSize);
struct table3D {
//All tables must be the same size for simplicity
byte xSize;
byte ySize;
byte **values;
int *axisX;
int *axisY;
int16_t *axisX;
int16_t *axisY;
//Store the last X and Y coordinates in the table. This is used to make the next check faster
byte lastXMax, lastXMin;
byte lastYMax, lastYMin;

View File

@ -144,6 +144,7 @@ void setPinMapping(byte boardID)
pinFuelPump = 4; //Fuel pump output
pinStepperDir = 16; //Direction pin for DRV8825 driver
pinStepperStep = 17; //Step pin for DRV8825 driver
pinStepperEnable = 26; //Enable pin for DRV8825
pinFan = A13; //Pin for the fan output
pinLaunch = 12; //Can be overwritten below
pinFlex = 2; // Flex sensor (Must be external interrupt enabled)
@ -178,9 +179,20 @@ void setPinMapping(byte boardID)
pinFuelPump = 45; //Fuel pump output (Goes to ULN2803)
pinStepperDir = 16; //Direction pin for DRV8825 driver
pinStepperStep = 17; //Step pin for DRV8825 driver
pinStepperEnable = 24; //Enable pin for DRV8825
pinFan = 47; //Pin for the fan output (Goes to ULN2803)
pinLaunch = 12; //Can be overwritten below
pinFlex = 2; // Flex sensor (Must be external interrupt enabled)
#if defined(CORE_TEENSY)
pinTrigger = 23;
pinStepperDir = 33;
pinCoil1 = 31;
pinTachOut = 28;
pinFan = 27;
pinCoil4 = 29;
pinCoil3 = 30;
#endif
break;
case 9:
@ -391,6 +403,7 @@ void setPinMapping(byte boardID)
pinMode(pinFan, OUTPUT);
pinMode(pinStepperDir, OUTPUT);
pinMode(pinStepperStep, OUTPUT);
pinMode(pinStepperEnable, OUTPUT);
pinMode(pinBoost, OUTPUT);
pinMode(pinVVT_1, OUTPUT);