Merge branch 'master' into dev_stm32F407VE

This commit is contained in:
Josh Stewart 2019-03-04 09:33:56 +11:00 committed by GitHub
commit 7a4c88068c
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
37 changed files with 6583 additions and 60242 deletions

View File

Before

Width:  |  Height:  |  Size: 47 KiB

After

Width:  |  Height:  |  Size: 47 KiB

View File

Before

Width:  |  Height:  |  Size: 205 KiB

After

Width:  |  Height:  |  Size: 205 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 152 KiB

View File

@ -8,8 +8,8 @@ G04 CONTOUR ON CENTER OF CONTOUR VECTOR*
%MOIN*%
%OFA0B0*%
%SFA1.0B1.0*%
%ADD10C,0.039370*%
%ADD11C,0.075000*%
%ADD10C,0.075000*%
%ADD11C,0.039370*%
%ADD12C,0.079370*%
%ADD13C,0.078000*%
%ADD14R,0.079370X0.079370*%
@ -23,9 +23,11 @@ G04 CONTOUR ON CENTER OF CONTOUR VECTOR*
G90*
G70*
G54D10*
X708Y897D03*
G54D11*
X580Y301D03*
X767Y664D03*
G54D11*
G54D10*
X592Y814D03*
X992Y814D03*
G54D12*
@ -37,19 +39,17 @@ X417Y514D03*
X717Y514D03*
X417Y414D03*
X717Y414D03*
G54D11*
G54D10*
X992Y914D03*
X592Y914D03*
G54D10*
G54D11*
X767Y314D03*
G54D13*
X892Y151D03*
X792Y151D03*
G54D10*
G54D11*
X542Y189D03*
X355Y326D03*
G54D11*
X708Y897D03*
G54D14*
X417Y714D03*
G54D15*
@ -387,17 +387,16 @@ X743Y989D01*
D02*
X267Y988D02*
X266Y988D01*
G54D18*
D02*
X686Y514D02*
X579Y514D01*
D02*
X579Y514D02*
X580Y320D01*
G54D19*
D02*
X618Y314D02*
X618Y302D01*
G54D18*
D02*
X579Y514D02*
X580Y320D01*
D02*
X686Y514D02*
X579Y514D01*
G36*
X184Y976D02*
X184Y974D01*

View File

@ -8,13 +8,12 @@ T102C0.038000
T103C0.035000
%
T100
X005421Y001885
X007671Y006635
X007671Y003135
X003546Y003260
X005796Y003010
X005421Y001885
T101
X004171Y005135
X007171Y006135
X007171Y004135
X004171Y006135
@ -22,13 +21,14 @@ X004171Y004135
X007171Y007135
X007171Y005135
X004171Y007135
X004171Y005135
T102
X008921Y001510
X007921Y001510
T103
X009921Y008135
X005921Y008135
X009921Y009135
X005921Y009135
X009921Y008135
T00
M30

View File

@ -0,0 +1,80 @@
*Pick And Place List
*Company=
*Author=
*eMail=
*
*Project=VR Conditioner v3
*Date=13:46:42
*CreatedBy=Fritzing 0.9.3b.04.19.5c895d327c44a3114e5fcc9d8260daf0cbb52806
*
*
*Coordinates in mm, always center of component
*Origin 0/0=Lower left corner of PCB
*Rotation in degree (0-360, math. pos.)
*
*No;Value;Package;X;Y;Rotation;Side;Name
1;;;7.2644;-19.3733;0;Bottom;Copper Fill16
2;;;18.5928;-4.28574;0;Bottom;Copper Fill28
3;0.01µF;0805 [SMD, multilayer];22.0984;-15.5844;0;Top;C2
4;;;15.9623;-12.8549;0;Bottom;TXT6
5;;;19.7866;-18.2811;0;Bottom;Copper Fill18
6;;;20.2946;-7.13054;0;Bottom;Copper Fill27
7;;;19.4858;-7.96443;0;Bottom;Via14
8;;;12.9286;-17.3413;0;Bottom;Copper Fill4
9;;;16.9926;-11.4485;0;Bottom;Copper Fill8
10;;;4.572;-23.9707;0;Bottom;Copper Fill14
11;1µF;0805 [SMD, multilayer];22.0984;-18.1244;0;Top;C3
12;4.7k;THT;20.1209;-20.6644;0;Bottom;R12
13;;;8.5344;-8.33704;0;Bottom;Copper Fill10
14;;;23.0391;-15.6173;-90;Bottom;TXT3
15;;;14.7234;-7.64693;0;Bottom;Via16
16;;;24.4094;-6.57174;0;Bottom;Copper Fill26
17;10k;0805 [SMD];20.5109;-25.4269;0;Top;R7
18;0.1µF;0805 [SMD, multilayer];22.0984;-13.0444;0;Top;C1
19;;;7.47785;-6.63903;0;Bottom;TXT4
20;;;10.287;-19.0685;0;Bottom;Copper Fill17
21;;;8.9789;-7.89254;0;Bottom;Copper Fill9
22;;;12.7;-19.3733;0;Bottom;Copper Fill2
23;;;11.6586;-14.4711;0;Bottom;Copper Fill23
24;;;17.5514;-4.83184;0;Bottom;Copper Fill36
25;;;21.082;-12.2613;0;Bottom;Copper Fill5
26;10k;0805 [SMD];9.08086;-23.2044;0;Top;R9
27;;;14.6685;-7.28294;0;Bottom;Copper Fill12
28;;;11.4554;-6.76224;0;Bottom;Copper Fill32
29;;;17.1704;-14.2933;0;Bottom;Copper Fill7
30;;;17.9832;-16.4015;0;Bottom;Copper Fill3
31;1nF;0805 [SMD, multilayer];7.03084;-14.3144;180;Top;C5
32;;;8.5344;-8.33704;0;Bottom;Copper Fill30
33;;;9.9568;-13.6837;0;Bottom;Copper Fill24
34;;;9.00835;-8.28193;0;Bottom;Via19
35;;;13.7709;-4.78943;0;Bottom;Via15
36;;;16.1823;-10.5259;0;Bottom;TXT6
37;;QSOP16;14.5583;-5.41172;180;Top;MAX9926
38;;;9.398;-8.33704;0;Bottom;Copper Fill11
39;1k;0805 [SMD];23.6133;-9.79693;90;Top;R4
40;;;11.4554;-5.49224;0;Bottom;Copper Fill35
41;;;9.6012;-13.7091;0;Bottom;Copper Fill15
42;;;19.4858;-16.8544;0;Bottom;Via17
43;;;22.1742;-8.04494;0;Bottom;Copper Fill25
44;;;21.336;-16.8587;0;Bottom;Copper Fill20
45;4.7k;THT;20.1209;-23.2044;180;Bottom;R10
46;;;17.1704;-16.8333;0;Bottom;Copper Fill6
47;;;17.2085;-3.37134;0;Bottom;Copper Fill34
48;;;17.5514;-6.76224;0;Bottom;Copper Fill33
49;;;6.00746;-7.5823;0;Bottom;TXT5
50;;;15.9512;-14.2933;0;Bottom;Copper Fill29
51;;;24.2316;-15.3601;0;Bottom;Copper Fill19
52;;;14.574;-25.1077;0;Bottom;TXT1
53;1nF;0805 [SMD, multilayer];6.15085;-24.2294;-90;Top;C4
54;;;8.2804;-14.3187;0;Bottom;Copper Fill22
55;;DIP (Dual Inline) [THT];14.4059;-14.3144;0;Bottom;IC1
56;1k;0805 [SMD];21.0733;-9.79693;90;Top;R6
57;;;15.5948;-17.8602;0;Bottom;TXT6
58;10k;0805 [SMD];7.17586;-16.8544;0;Top;R13
59;;;13.9954;-14.4965;0;Bottom;Copper Fill1
60;;THT;21.3909;-3.83692;90;Bottom;J1
61;;;15.4313;-15.285;0;Bottom;TXT6
62;;;19.8374;-16.9222;0;Bottom;Copper Fill13
63;;;9.398;-8.33704;0;Bottom;Copper Fill31
64;10k;0805 [SMD];7.17586;-11.7744;0;Top;R11
65;;;20.701;-13.7599;0;Bottom;Copper Fill21

File diff suppressed because it is too large Load Diff

View File

@ -1,77 +0,0 @@
*Pick And Place List
*Company=
*Author=
*eMail=
*
*Project=VR Conditioner v3
*Date=22:29:16
*CreatedBy=Fritzing 0.9.3b.04.19.5c895d327c44a3114e5fcc9d8260daf0cbb52806
*
*
*Coordinates in mm, always center of component
*Origin 0/0=Lower left corner of PCB
*Rotation in degree (0-360, math. pos.)
*
*No;Value;Package;X;Y;Rotation;Side;Name
1;;;17.1704;-14.2933;0;Bottom;Copper Fill7
2;;;9.398;-8.33704;0;Bottom;Copper Fill11
3;;;21.082;-12.2613;0;Bottom;Copper Fill5
4;;;20.701;-13.7599;0;Bottom;Copper Fill21
5;;;24.4094;-6.57174;0;Bottom;Copper Fill26
6;1k;0805 [SMD];23.6133;-9.79693;90;Top;R4
7;;;17.1704;-16.8333;0;Bottom;Copper Fill6
8;;;8.2804;-14.3187;0;Bottom;Copper Fill22
9;10k;0805 [SMD];9.08086;-23.2044;0;Top;R9
10;4.7k;THT;20.1209;-20.6644;0;Bottom;R12
11;;;7.47785;-6.63903;0;Bottom;TXT4
12;0.1µF;0805 [SMD, multilayer];22.0984;-13.0444;0;Top;C1
13;;;8.5344;-8.33704;0;Bottom;Copper Fill30
14;;;8.5344;-8.33704;0;Bottom;Copper Fill10
15;;;13.9954;-14.4965;0;Bottom;Copper Fill1
16;;;13.7709;-4.78943;0;Bottom;Via15
17;;;14.7234;-7.64693;0;Bottom;Via16
18;;;16.9926;-11.4485;0;Bottom;Copper Fill8
19;;;10.287;-19.0685;0;Bottom;Copper Fill17
20;1nF;0805 [SMD, multilayer];7.03084;-14.3144;180;Top;C5
21;;QSOP16;14.5583;-5.41172;180;Top;MAX9926
22;10k;0805 [SMD];7.17586;-11.7744;0;Top;R11
23;4.7k;THT;20.1209;-23.2044;180;Bottom;R10
24;;;20.2946;-7.13054;0;Bottom;Copper Fill27
25;;;7.2644;-19.3733;0;Bottom;Copper Fill16
26;;;17.2085;-3.37134;0;Bottom;Copper Fill34
27;10k;0805 [SMD];7.17586;-16.8544;0;Top;R13
28;;;22.1568;-12.723;-90;Bottom;IMG1
29;;;9.9568;-13.6837;0;Bottom;Copper Fill24
30;10k;0805 [SMD];20.5109;-25.4269;0;Top;R7
31;1k;0805 [SMD];21.0733;-9.79693;90;Top;R6
32;;;12.9286;-17.3413;0;Bottom;Copper Fill4
33;;;25.6195;-12.6698;-90;Bottom;TXT3
34;;;18.5928;-4.28574;0;Bottom;Copper Fill28
35;1µF;0805 [SMD, multilayer];22.0984;-18.1244;0;Top;C3
36;;;4.572;-23.9707;0;Bottom;Copper Fill14
37;;;8.9789;-7.89254;0;Bottom;Copper Fill9
38;;;6.00745;-7.5823;0;Bottom;TXT5
39;;;17.5514;-6.76224;0;Bottom;Copper Fill33
40;;DIP (Dual Inline) [THT];14.4059;-14.3144;0;Bottom;IC1
41;;;14.2736;-25.0931;0;Bottom;TXT1
42;;;14.6685;-7.28294;0;Bottom;Copper Fill12
43;;;11.6586;-14.4711;0;Bottom;Copper Fill23
44;;;11.4554;-6.76224;0;Bottom;Copper Fill32
45;;;9.00836;-8.28192;0;Bottom;Via19
46;;;19.4858;-7.96443;0;Bottom;Via14
47;;;15.9512;-14.2933;0;Bottom;Copper Fill29
48;;;22.1742;-8.04494;0;Bottom;Copper Fill25
49;;;19.7866;-18.2811;0;Bottom;Copper Fill18
50;;;24.2316;-15.3601;0;Bottom;Copper Fill19
51;;;11.4554;-5.49224;0;Bottom;Copper Fill35
52;;;12.7;-19.3733;0;Bottom;Copper Fill2
53;;;9.398;-8.33704;0;Bottom;Copper Fill31
54;;;19.4858;-16.8544;0;Bottom;Via17
55;0.01µF;0805 [SMD, multilayer];22.0984;-15.5844;0;Top;C2
56;;;9.6012;-13.7091;0;Bottom;Copper Fill15
57;;;17.9832;-16.4015;0;Bottom;Copper Fill3
58;1nF;0805 [SMD, multilayer];6.15085;-24.2294;-90;Top;C4
59;;;17.5514;-4.83184;0;Bottom;Copper Fill36
60;;;21.336;-16.8587;0;Bottom;Copper Fill20
61;;THT;21.3909;-3.83692;90;Bottom;J1
62;;;19.8374;-16.9222;0;Bottom;Copper Fill13

View File

@ -6,7 +6,7 @@
MTversion = 2.25
queryCommand = "Q"
signature = "speeduino 201902"
signature = "speeduino 201903-dev"
versionInfo = "S" ;This info is what is displayed to user
[TunerStudio]

View File

@ -25,17 +25,17 @@ void fanControl();
#define READ_N2O_ARM_PIN() ((*n2o_arming_pin_port & n2o_arming_pin_mask) ? true : false)
volatile PORT_TYPE *boost_pin_port;
volatile PINMAKS_TYPE boost_pin_mask;
volatile PINMASK_TYPE boost_pin_mask;
volatile PORT_TYPE *vvt_pin_port;
volatile PINMAKS_TYPE vvt_pin_mask;
volatile PINMASK_TYPE vvt_pin_mask;
volatile PORT_TYPE *fan_pin_port;
volatile PINMAKS_TYPE fan_pin_mask;
volatile PINMASK_TYPE fan_pin_mask;
volatile PORT_TYPE *n2o_stage1_pin_port;
volatile PINMAKS_TYPE n2o_stage1_pin_mask;
volatile PINMASK_TYPE n2o_stage1_pin_mask;
volatile PORT_TYPE *n2o_stage2_pin_port;
volatile PINMAKS_TYPE n2o_stage2_pin_mask;
volatile PINMASK_TYPE n2o_stage2_pin_mask;
volatile PORT_TYPE *n2o_arming_pin_port;
volatile PINMAKS_TYPE n2o_arming_pin_mask;
volatile PINMASK_TYPE n2o_arming_pin_mask;
volatile bool boost_pwm_state;
unsigned int boost_pwm_max_count; //Used for variable PWM frequency

View File

@ -10,7 +10,7 @@
* General
*/
#define PORT_TYPE uint8_t //Size of the port variables (Eg inj1_pin_port).
#define PINMAKS_TYPE uint8_t
#define PINMASK_TYPE uint8_t
void initBoard();
uint16_t freeRam();

View File

@ -1,22 +1,29 @@
#ifndef STM32_H
#define STM32_H
#if defined(CORE_STM32) && !defined(ARDUINO_BLACK_F407VE)
#if defined(CORE_STM32)
#include <Fram.h>
/*
***********************************************************************************************************
* General
*/
#define PORT_TYPE uint32_t
#define PINMAKS_TYPE uint32_t
#define PINMASK_TYPE uint32_t
#define micros_safe() micros() //timer5 method is not used on anything but AVR, the micros_safe() macro is simply an alias for the normal micros()
#ifndef USE_SERIAL3
#define USE_SERIAL3
#endif
void initBoard();
uint16_t freeRam();
#if defined(USE_STM32GENERIC)
#ifndef Serial
#define Serial Serial1
#endif
#if defined(ARDUINO_BLACK_F407VE) || defined(STM32F4) || defined(_STM32F4_)
FramClass EEPROM(PB0, PB3, PB4, PB5, 15000000);
#endif
//Much of the below is not correct, but included to allow compilation
//STM32F1/variants/.../board.cpp
#if defined (STM32F4)
@ -60,12 +67,26 @@
/*
***********************************************************************************************************
* Schedules
* Timers Table for STM32F1
* TIMER1 TIMER2 TIMER3 TIMER4
* 1 - 1 - INJ1 1 - IGN1 1 - oneMSInterval
* 2 - BOOST 2 - INJ2 2 - IGN2 2 -
* 3 - VVT 3 - INJ3 3 - IGN3 3 -
* 4 - IDLE 4 - INJ4 4 - IGN4 4 -
*
* Timers Table for STM32F4
* TIMER1 TIMER2 TIMER3 TIMER4 TIMER5 TIMER8
* 1 - 1 - INJ1 1 - IGN1 1 - IGN5 1 - INJ5 1 - oneMSInterval
* 2 - BOOST 2 - INJ2 2 - IGN2 2 - IGN6 2 - INJ6 2 -
* 3 - VVT 3 - INJ3 3 - IGN3 3 - IGN7 3 - INJ7 3 -
* 4 - IDLE 4 - INJ4 4 - IGN4 4 - IGN8 4 - INJ8 4 -
*
*/
#define MAX_TIMER_PERIOD 131070 //The longest period of time (in uS) that the timer can permit (IN this case it is 65535 * 2, as each timer tick is 2uS)
#define MAX_TIMER_PERIOD_SLOW 131070 //The longest period of time (in uS) that the timer can permit (IN this case it is 65535 * 2, as each timer tick is 2uS)
#define MAX_TIMER_PERIOD 65535*2 //The longest period of time (in uS) that the timer can permit (IN this case it is 65535 * 2, as each timer tick is 2uS)
#define MAX_TIMER_PERIOD_SLOW 65535*2 //The longest period of time (in uS) that the timer can permit (IN this case it is 65535 * 2, as each timer tick is 2uS)
#define uS_TO_TIMER_COMPARE(uS) (uS >> 1) //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 >> 1) //Converts a given number of uS into the required number of timer ticks until that time has passed.
#if defined(ARDUINO_ARCH_STM32) // STM32GENERIC core
#if defined(ARDUINO_ARCH_STM32) && !defined(_VARIANT_ARDUINO_STM32_) // STM32GENERIC core
#define FUEL1_COUNTER (TIM2)->CNT
#define FUEL2_COUNTER (TIM2)->CNT
#define FUEL3_COUNTER (TIM2)->CNT
@ -239,7 +260,7 @@
***********************************************************************************************************
* Auxilliaries
*/
#if defined(ARDUINO_ARCH_STM32) // STM32GENERIC core
#if defined(ARDUINO_ARCH_STM32) && !defined(_VARIANT_ARDUINO_STM32_) // STM32GENERIC core
#define ENABLE_BOOST_TIMER() (TIM1)->CCER |= TIM_CCER_CC2E
#define DISABLE_BOOST_TIMER() (TIM1)->CCER &= ~TIM_CCER_CC2E
@ -267,7 +288,7 @@
***********************************************************************************************************
* Idle
*/
#if defined(ARDUINO_ARCH_STM32) // STM32GENERIC core
#if defined(ARDUINO_ARCH_STM32) && !defined(_VARIANT_ARDUINO_STM32_) // STM32GENERIC core
#define IDLE_COUNTER (TIM1)->CNT
#define IDLE_COMPARE (TIM1)->CCR4

View File

@ -5,8 +5,8 @@
#include "idle.h"
#include "scheduler.h"
#include "HardwareTimer.h"
#if defined(STM32F4)
//These should really be in the stm32GENERIC libs, but for somereason they only have timers 1-4
#if defined(ARDUINO_ARCH_STM32) && defined(STM32_CORE_VERSION)
//These should really be in the stm32 libmaple libs, but for somereason they only have timers 1-4
#include <stm32_TIM_variant_11.h>
HardwareTimer Timer5(TIM5, chip_tim5, sizeof(chip_tim5) / sizeof(chip_tim5[0]));
HardwareTimer Timer8(TIM8, chip_tim8, sizeof(chip_tim8) / sizeof(chip_tim8[0]));
@ -18,9 +18,10 @@ void initBoard()
***********************************************************************************************************
* General
*/
#define FLASH_LENGTH 8192
#ifndef FLASH_LENGTH
#define FLASH_LENGTH 8192
#endif
delay(10);
/*
***********************************************************************************************************
* Idle
@ -33,8 +34,7 @@ void initBoard()
//This must happen at the end of the idle init
Timer1.setMode(4, TIMER_OUTPUT_COMPARE);
//timer_set_mode(TIMER1, 4, TIMER_OUTPUT_COMPARE;
if(idle_pwm_max_count > 0) { Timer1.attachInterrupt(4, idleInterrupt);} //on first flash the configPage4.iacAlgorithm is invalid
Timer1.resume();
if(idle_pwm_max_count > 0) { Timer1.attachInterrupt(4, idleInterrupt); } //on first flash the configPage4.iacAlgorithm is invalid
/*
@ -67,32 +67,23 @@ void initBoard()
Timer1.setMode(3, TIMER_OUTPUT_COMPARE);
if(boost_pwm_max_count > 0) { Timer1.attachInterrupt(2, boostInterrupt);}
if(vvt_pwm_max_count > 0) { Timer1.attachInterrupt(3, vvtInterrupt);}
Timer1.resume();
/*
***********************************************************************************************************
* Schedules
*/
#if defined(ARDUINO_ARCH_STM32) // STM32GENERIC core
//see https://github.com/rogerclarkmelbourne/Arduino_STM32/blob/754bc2969921f1ef262bd69e7faca80b19db7524/STM32F1/system/libmaple/include/libmaple/timer.h#L444
Timer1.setPrescaleFactor((HAL_RCC_GetHCLKFreq() * 2U)-1); //2us resolution
Timer2.setPrescaleFactor((HAL_RCC_GetHCLKFreq() * 2U)-1); //2us resolution
Timer3.setPrescaleFactor((HAL_RCC_GetHCLKFreq() * 2U)-1); //2us resolution
#else //libmaple core aka STM32DUINO
//see https://github.com/rogerclarkmelbourne/Arduino_STM32/blob/754bc2969921f1ef262bd69e7faca80b19db7524/STM32F1/system/libmaple/include/libmaple/timer.h#L444
#if defined (STM32F1) || defined(__STM32F1__)
//(CYCLES_PER_MICROSECOND == 72, APB2 at 72MHz, APB1 at 36MHz).
//Timer2 to 4 is on APB1, Timer1 on APB2. http://www.st.com/resource/en/datasheet/stm32f103cb.pdf sheet 12
Timer1.setPrescaleFactor((72 * 2U)-1); //2us resolution
Timer2.setPrescaleFactor((36 * 2U)-1); //2us resolution
Timer3.setPrescaleFactor((36 * 2U)-1); //2us resolution
#elif defined(STM32F4)
//(CYCLES_PER_MICROSECOND == 168, APB2 at 84MHz, APB1 at 42MHz).
//Timer2 to 14 is on APB1, Timers 1, 8, 9 and 10 on APB2. http://www.st.com/resource/en/datasheet/stm32f407vg.pdf sheet 120
Timer1.setPrescaleFactor((84 * 2U)-1); //2us resolution
Timer2.setPrescaleFactor((42 * 2U)-1); //2us resolution
Timer3.setPrescaleFactor((42 * 2U)-1); //2us resolution
#endif
#if defined (STM32F1) || defined(__STM32F1__)
//(CYCLES_PER_MICROSECOND == 72, APB2 at 72MHz, APB1 at 36MHz).
//Timer2 to 4 is on APB1, Timer1 on APB2. http://www.st.com/resource/en/datasheet/stm32f103cb.pdf sheet 12
Timer1.setPrescaleFactor((72 * 2)-1); //2us resolution
Timer2.setPrescaleFactor((36 * 2)-1); //2us resolution
Timer3.setPrescaleFactor((36 * 2)-1); //2us resolution
#elif defined(STM32F4)
//(CYCLES_PER_MICROSECOND == 168, APB2 at 84MHz, APB1 at 42MHz).
//Timer2 to 14 is on APB1, Timers 1, 8, 9 and 10 on APB2. http://www.st.com/resource/en/datasheet/stm32f407vg.pdf sheet 120
Timer1.setPrescaleFactor((168 * 2)-1); //2us resolution
Timer2.setPrescaleFactor((84 * 2)-1); //2us resolution
Timer3.setPrescaleFactor((84 * 2)-1); //2us resolution
#endif
Timer2.setMode(1, TIMER_OUTPUT_COMPARE);
Timer2.setMode(2, TIMER_OUTPUT_COMPARE);
@ -112,51 +103,56 @@ void initBoard()
Timer2.attachInterrupt(3, fuelSchedule3Interrupt);
Timer2.attachInterrupt(4, fuelSchedule4Interrupt);
#if (INJ_CHANNELS >= 5)
Timer5.setMode(1, TIMER_OUTPUT_COMPARE);
Timer5.attachInterrupt(1, fuelSchedule5Interrupt);
#endif
#if (INJ_CHANNELS >= 6)
Timer5.setMode(2, TIMER_OUTPUT_COMPARE);
Timer5.attachInterrupt(2, fuelSchedule6Interrupt);
#endif
#if (INJ_CHANNELS >= 7)
Timer5.setMode(3, TIMER_OUTPUT_COMPARE);
Timer5.attachInterrupt(3, fuelSchedule7Interrupt);
#endif
#if (INJ_CHANNELS >= 8)
Timer5.setMode(4, TIMER_OUTPUT_COMPARE);
Timer5.attachInterrupt(4, fuelSchedule8Interrupt);
#endif
//Ignition
#if (IGN_CHANNELS >= 1)
Timer3.attachInterrupt(1, ignitionSchedule1Interrupt);
#endif
#if (IGN_CHANNELS >= 2)
Timer3.attachInterrupt(2, ignitionSchedule2Interrupt);
#endif
#if (IGN_CHANNELS >= 3)
Timer3.attachInterrupt(3, ignitionSchedule3Interrupt);
#endif
#if (IGN_CHANNELS >= 4)
Timer3.attachInterrupt(4, ignitionSchedule4Interrupt);
#endif
#if (IGN_CHANNELS >= 5)
Timer4.setMode(1, TIMER_OUTPUT_COMPARE);
Timer4.attachInterrupt(1, ignitionSchedule5Interrupt);
#endif
#if (IGN_CHANNELS >= 6)
Timer4.setMode(2, TIMER_OUTPUT_COMPARE);
Timer4.attachInterrupt(2, ignitionSchedule6Interrupt);
#endif
#if (IGN_CHANNELS >= 7)
Timer4.setMode(3, TIMER_OUTPUT_COMPARE);
Timer4.attachInterrupt(3, ignitionSchedule7Interrupt);
#endif
#if (IGN_CHANNELS >= 8)
Timer4.setMode(4, TIMER_OUTPUT_COMPARE);
Timer4.attachInterrupt(4, ignitionSchedule8Interrupt);
#endif
Timer1.setOverflow(0xFFFF);
Timer1.resume();
Timer2.setOverflow(0xFFFF);
Timer2.resume();
Timer3.setOverflow(0xFFFF);
Timer3.resume();
#if (IGN_CHANNELS >= 5)
Timer4.setOverflow(0xFFFF);
Timer4.resume();
#endif
#if (INJ_CHANNELS >= 5)
Timer5.setOverflow(0xFFFF);
Timer5.resume();
#endif
}

View File

@ -9,7 +9,7 @@
void initBoard();
uint16_t freeRam();
#define PORT_TYPE uint8_t //Size of the port variables
#define PINMAKS_TYPE uint8_t
#define PINMASK_TYPE uint8_t
#define BOARD_DIGITAL_GPIO_PINS 34
#define BOARD_NR_GPIO_PINS 34
#define USE_SERIAL3

View File

@ -7,7 +7,7 @@
* General
*/
#define PORT_TYPE uint32_t //Size of the port variables (Eg inj1_pin_port). Most systems use a byte, but SAMD21 and possibly others are a 32-bit unsigned int
#define PINMAKS_TYPE uint32_t
#define PINMASK_TYPE uint32_t
#define BOARD_NR_GPIO_PINS 52 //Not sure this is correct
#define BOARD_DIGITAL_GPIO_PINS 52 //Pretty sure this isn't right
#define micros_safe() micros() //timer5 method is not used on anything but AVR, the micros_safe() macro is simply an alias for the normal micros()

View File

@ -14,8 +14,8 @@ uint8_t Glow, Ghigh;
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
HardwareSerial &CANSerial = Serial3;
#elif defined(CORE_STM32) && !defined(ARDUINO_BLACK_F407VE)
#if defined(ARDUINO_ARCH_STM32) // STM32GENERIC core
#elif defined(CORE_STM32)
#if defined(ARDUINO_ARCH_STM32) && !defined(_VARIANT_ARDUINO_STM32_) // STM32GENERIC core
SerialUART &CANSerial = Serial2;
#else //libmaple core aka STM32DUINO
HardwareSerial &CANSerial = Serial2;

View File

@ -11,6 +11,7 @@ A full copy of the license may be found in the projects root directory
#include "maths.h"
#include "utils.h"
#include "decoders.h"
#include "scheduledIO.h"
/*
Processes the data on the serial buffer.
@ -195,7 +196,7 @@ void command()
break;
case 'Q': // send code version
Serial.print(F("speeduino 201902"));
Serial.print(F("speeduino 201903-dev"));
break;
case 'r': //New format for the optimised OutputChannels
@ -225,7 +226,7 @@ void command()
break;
case 'S': // send code version
Serial.print(F("Speeduino 2019.02"));
Serial.print(F("Speeduino 2019.03-dev"));
currentStatus.secl = 0; //This is required in TS3 due to its stricter timings
break;
@ -1514,14 +1515,14 @@ void commandButtons()
{
case 256: // cmd is stop
BIT_CLEAR(currentStatus.testOutputs, 1);
digitalWrite(pinInjector1, LOW);
digitalWrite(pinInjector2, LOW);
digitalWrite(pinInjector3, LOW);
digitalWrite(pinInjector4, LOW);
digitalWrite(pinCoil1, LOW);
digitalWrite(pinCoil2, LOW);
digitalWrite(pinCoil3, LOW);
digitalWrite(pinCoil4, LOW);
endCoil1Charge();
endCoil2Charge();
endCoil3Charge();
endCoil4Charge();
closeInjector1();
closeInjector2();
closeInjector3();
closeInjector4();
break;
case 257: // cmd is enable
@ -1529,10 +1530,10 @@ void commandButtons()
BIT_SET(currentStatus.testOutputs, 1);
break;
case 513: // cmd group is for injector1 on actions
if( BIT_CHECK(currentStatus.testOutputs, 1) ){ digitalWrite(pinInjector1, HIGH); }
if( BIT_CHECK(currentStatus.testOutputs, 1) ){ openInjector1(); }
break;
case 514: // cmd group is for injector1 off actions
if( BIT_CHECK(currentStatus.testOutputs, 1) ){digitalWrite(pinInjector1, LOW);}
if( BIT_CHECK(currentStatus.testOutputs, 1) ){ closeInjector1(); }
break;
case 515: // cmd group is for injector1 50% dc actions
//for (byte dcloop = 0; dcloop < 11; dcloop++)
@ -1544,64 +1545,64 @@ void commandButtons()
//}
break;
case 516: // cmd group is for injector2 on actions
if( BIT_CHECK(currentStatus.testOutputs, 1) ){ digitalWrite(pinInjector2, HIGH); }
if( BIT_CHECK(currentStatus.testOutputs, 1) ){ openInjector2(); }
break;
case 517: // cmd group is for injector2 off actions
if( BIT_CHECK(currentStatus.testOutputs, 1) ){ digitalWrite(pinInjector2, LOW); }
if( BIT_CHECK(currentStatus.testOutputs, 1) ){ closeInjector2(); }
break;
case 518: // cmd group is for injector2 50%dc actions
break;
case 519: // cmd group is for injector3 on actions
if( BIT_CHECK(currentStatus.testOutputs, 1) ) { digitalWrite(pinInjector3, HIGH); }
if( BIT_CHECK(currentStatus.testOutputs, 1) ){ openInjector3(); }
break;
case 520: // cmd group is for injector3 off actions
if( BIT_CHECK(currentStatus.testOutputs, 1) ) { digitalWrite(pinInjector3, LOW); }
if( BIT_CHECK(currentStatus.testOutputs, 1) ){ closeInjector3(); }
break;
case 521: // cmd group is for injector3 50%dc actions
break;
case 522: // cmd group is for injector4 on actions
if( BIT_CHECK(currentStatus.testOutputs, 1) ){ digitalWrite(pinInjector4, HIGH); }
if( BIT_CHECK(currentStatus.testOutputs, 1) ){ openInjector4(); }
break;
case 523: // cmd group is for injector4 off actions
if( BIT_CHECK(currentStatus.testOutputs, 1) ){ digitalWrite(pinInjector4, LOW); }
if( BIT_CHECK(currentStatus.testOutputs, 1) ){ closeInjector4(); }
break;
case 524: // cmd group is for injector4 50% dc actions
break;
case 769: // cmd group is for spark1 on actions
if( BIT_CHECK(currentStatus.testOutputs, 1) ) { digitalWrite(pinCoil1, HIGH); }
if( BIT_CHECK(currentStatus.testOutputs, 1) ) { digitalWrite(pinCoil1, coilHIGH); }
break;
case 770: // cmd group is for spark1 off actions
if( BIT_CHECK(currentStatus.testOutputs, 1) ) { digitalWrite(pinCoil1, LOW); }
if( BIT_CHECK(currentStatus.testOutputs, 1) ) { digitalWrite(pinCoil1, coilLOW); }
break;
case 771: // cmd group is for spark1 50%dc actions
break;
case 772: // cmd group is for spark2 on actions
if( BIT_CHECK(currentStatus.testOutputs, 1) ) { digitalWrite(pinCoil2, HIGH); }
if( BIT_CHECK(currentStatus.testOutputs, 1) ) { digitalWrite(pinCoil2, coilHIGH); }
break;
case 773: // cmd group is for spark2 off actions
if( BIT_CHECK(currentStatus.testOutputs, 1) ) { digitalWrite(pinCoil2, LOW); }
if( BIT_CHECK(currentStatus.testOutputs, 1) ) { digitalWrite(pinCoil2, coilLOW); }
break;
case 774: // cmd group is for spark2 50%dc actions
break;
case 775: // cmd group is for spark3 on actions
if( BIT_CHECK(currentStatus.testOutputs, 1) ) { digitalWrite(pinCoil3, HIGH); }
if( BIT_CHECK(currentStatus.testOutputs, 1) ) { digitalWrite(pinCoil3, coilHIGH); }
break;
case 776: // cmd group is for spark3 off actions
if( BIT_CHECK(currentStatus.testOutputs, 1) ) { digitalWrite(pinCoil3, LOW); }
if( BIT_CHECK(currentStatus.testOutputs, 1) ) { digitalWrite(pinCoil3, coilLOW); }
break;
case 777: // cmd group is for spark3 50%dc actions
break;
case 778: // cmd group is for spark4 on actions
if( BIT_CHECK(currentStatus.testOutputs, 1) ) { digitalWrite(pinCoil4, HIGH); }
if( BIT_CHECK(currentStatus.testOutputs, 1) ) { digitalWrite(pinCoil4, coilHIGH); }
break;
case 779: // cmd group is for spark4 off actions
if( BIT_CHECK(currentStatus.testOutputs, 1) ) { digitalWrite(pinCoil4, LOW); }
if( BIT_CHECK(currentStatus.testOutputs, 1) ) { digitalWrite(pinCoil4, coilLOW); }
break;
case 780: // cmd group is for spark4 50%dc actions

View File

@ -434,22 +434,22 @@ void triggerSetEndTeeth_missingTooth()
byte toothAdder = 0;
if( (configPage4.sparkMode == IGN_MODE_SEQUENTIAL) && (configPage4.TrigSpeed == CRANK_SPEED) ) { toothAdder = configPage4.triggerTeeth; }
ignition1EndTooth = ( (ignition1EndAngle - configPage4.triggerAngle) / triggerToothAngle ) - 1;
ignition1EndTooth = ( (ignition1EndAngle - configPage4.triggerAngle) / (int16_t)(triggerToothAngle) ) - 1;
if(ignition1EndTooth > (configPage4.triggerTeeth + toothAdder)) { ignition1EndTooth -= (configPage4.triggerTeeth + toothAdder); }
if(ignition1EndTooth <= 0) { ignition1EndTooth += (configPage4.triggerTeeth + toothAdder); }
if(ignition1EndTooth > (triggerActualTeeth + toothAdder)) { ignition1EndTooth = (triggerActualTeeth + toothAdder); }
ignition2EndTooth = ( (ignition2EndAngle - configPage4.triggerAngle) / triggerToothAngle ) - 1;
ignition2EndTooth = ( (ignition2EndAngle - configPage4.triggerAngle) / (int16_t)(triggerToothAngle) ) - 1;
if(ignition2EndTooth > (configPage4.triggerTeeth + toothAdder)) { ignition2EndTooth -= (configPage4.triggerTeeth + toothAdder); }
if(ignition2EndTooth <= 0) { ignition2EndTooth += (configPage4.triggerTeeth + toothAdder); }
if(ignition2EndTooth > (triggerActualTeeth + toothAdder)) { ignition2EndTooth = (triggerActualTeeth + toothAdder); }
ignition3EndTooth = ( (ignition3EndAngle - configPage4.triggerAngle) / triggerToothAngle ) - 1;
ignition3EndTooth = ( (ignition3EndAngle - configPage4.triggerAngle) / (int16_t)(triggerToothAngle) ) - 1;
if(ignition3EndTooth > (configPage4.triggerTeeth + toothAdder)) { ignition3EndTooth -= (configPage4.triggerTeeth + toothAdder); }
if(ignition3EndTooth <= 0) { ignition3EndTooth += (configPage4.triggerTeeth + toothAdder); }
if(ignition3EndTooth > (triggerActualTeeth + toothAdder)) { ignition3EndTooth = (triggerActualTeeth + toothAdder); }
ignition4EndTooth = ( (ignition4EndAngle - configPage4.triggerAngle) / triggerToothAngle ) - 1;
ignition4EndTooth = ( (ignition4EndAngle - configPage4.triggerAngle) / (int16_t)(triggerToothAngle) ) - 1;
if(ignition4EndTooth > (configPage4.triggerTeeth + toothAdder)) { ignition4EndTooth -= (configPage4.triggerTeeth + toothAdder); }
if(ignition4EndTooth <= 0) { ignition4EndTooth += (configPage4.triggerTeeth + toothAdder); }
if(ignition4EndTooth > (triggerActualTeeth + toothAdder)) { ignition4EndTooth = (triggerActualTeeth + toothAdder); }
@ -592,22 +592,22 @@ void triggerSetEndTeeth_DualWheel()
byte toothAdder = 0;
if( (configPage4.sparkMode == IGN_MODE_SEQUENTIAL) && (configPage4.TrigSpeed == CRANK_SPEED) ) { toothAdder = configPage4.triggerTeeth; }
ignition1EndTooth = ( (ignition1EndAngle - configPage4.triggerAngle) / triggerToothAngle ) - 1;
ignition1EndTooth = ( (ignition1EndAngle - configPage4.triggerAngle) / (int16_t)(triggerToothAngle) ) - 1;
if(ignition1EndTooth > (configPage4.triggerTeeth + toothAdder)) { ignition1EndTooth -= (configPage4.triggerTeeth + toothAdder); }
if(ignition1EndTooth <= 0) { ignition1EndTooth += configPage4.triggerTeeth; }
if(ignition1EndTooth > (triggerActualTeeth + toothAdder)) { ignition1EndTooth = (triggerActualTeeth + toothAdder); }
ignition2EndTooth = ( (ignition2EndAngle - configPage4.triggerAngle) / triggerToothAngle ) - 1;
ignition2EndTooth = ( (ignition2EndAngle - configPage4.triggerAngle) / (int16_t)(triggerToothAngle) ) - 1;
if(ignition2EndTooth > (configPage4.triggerTeeth + toothAdder)) { ignition2EndTooth -= (configPage4.triggerTeeth + toothAdder); }
if(ignition2EndTooth <= 0) { ignition2EndTooth += configPage4.triggerTeeth; }
if(ignition1EndTooth > (triggerActualTeeth + toothAdder)) { ignition3EndTooth = (triggerActualTeeth + toothAdder); }
ignition3EndTooth = ( (ignition3EndAngle - configPage4.triggerAngle) / triggerToothAngle ) - 1;
ignition3EndTooth = ( (ignition3EndAngle - configPage4.triggerAngle) / (int16_t)(triggerToothAngle) ) - 1;
if(ignition3EndTooth > (configPage4.triggerTeeth + toothAdder)) { ignition3EndTooth -= (configPage4.triggerTeeth + toothAdder); }
if(ignition3EndTooth <= 0) { ignition3EndTooth += configPage4.triggerTeeth; }
if(ignition3EndTooth > (triggerActualTeeth + toothAdder)) { ignition3EndTooth = (triggerActualTeeth + toothAdder); }
ignition4EndTooth = ( (ignition4EndAngle - configPage4.triggerAngle) / triggerToothAngle ) - 1;
ignition4EndTooth = ( (ignition4EndAngle - configPage4.triggerAngle) / (int16_t)(triggerToothAngle) ) - 1;
if(ignition4EndTooth > (configPage4.triggerTeeth + toothAdder)) { ignition4EndTooth -= (configPage4.triggerTeeth + toothAdder); }
if(ignition4EndTooth <= 0) { ignition4EndTooth += configPage4.triggerTeeth; }
if(ignition4EndTooth > (triggerActualTeeth + toothAdder)) { ignition4EndTooth = (triggerActualTeeth + toothAdder); }

View File

@ -48,11 +48,11 @@
#define SMALL_FLASH_MODE
#endif
#if __GNUC__ < 7 //Already included on GCC 7
extern "C" char* sbrk(int incr); //Used to freeRam
#if defined(ARDUINO_ARCH_STM32) // STM32GENERIC core
//inline unsigned char digitalPinToInterrupt(unsigned char Interrupt_pin) { return Interrupt_pin; } //This isn't included in the stm32duino libs (yet)
// #define portOutputRegister(port) (volatile byte *)( &(port->ODR) )
// #define portInputRegister(port) (volatile byte *)( &(port->IDR) )
#endif
#if !defined(_VARIANT_ARDUINO_STM32_) // STM32GENERIC core
inline unsigned char digitalPinToInterrupt(unsigned char Interrupt_pin) { return Interrupt_pin; } //This isn't included in the stm32duino libs (yet)
#else //libmaple core aka STM32DUINO
//These are defined in STM32F1/variants/generic_stm32f103c/variant.h but return a non byte* value
#define portOutputRegister(port) (volatile byte *)( &(port->regs->ODR) )
@ -252,48 +252,48 @@ struct table2D knockWindowDurationTable;
//These are for the direct port manipulation of the injectors, coils and aux outputs
volatile PORT_TYPE *inj1_pin_port;
volatile PINMAKS_TYPE inj1_pin_mask;
volatile PINMASK_TYPE inj1_pin_mask;
volatile PORT_TYPE *inj2_pin_port;
volatile PINMAKS_TYPE inj2_pin_mask;
volatile PINMASK_TYPE inj2_pin_mask;
volatile PORT_TYPE *inj3_pin_port;
volatile PINMAKS_TYPE inj3_pin_mask;
volatile PINMASK_TYPE inj3_pin_mask;
volatile PORT_TYPE *inj4_pin_port;
volatile PINMAKS_TYPE inj4_pin_mask;
volatile PINMASK_TYPE inj4_pin_mask;
volatile PORT_TYPE *inj5_pin_port;
volatile PINMAKS_TYPE inj5_pin_mask;
volatile PINMASK_TYPE inj5_pin_mask;
volatile PORT_TYPE *inj6_pin_port;
volatile PINMAKS_TYPE inj6_pin_mask;
volatile PINMASK_TYPE inj6_pin_mask;
volatile PORT_TYPE *inj7_pin_port;
volatile PINMAKS_TYPE inj7_pin_mask;
volatile PINMASK_TYPE inj7_pin_mask;
volatile PORT_TYPE *inj8_pin_port;
volatile PINMAKS_TYPE inj8_pin_mask;
volatile PINMASK_TYPE inj8_pin_mask;
volatile PORT_TYPE *ign1_pin_port;
volatile PINMAKS_TYPE ign1_pin_mask;
volatile PINMASK_TYPE ign1_pin_mask;
volatile PORT_TYPE *ign2_pin_port;
volatile PINMAKS_TYPE ign2_pin_mask;
volatile PINMASK_TYPE ign2_pin_mask;
volatile PORT_TYPE *ign3_pin_port;
volatile PINMAKS_TYPE ign3_pin_mask;
volatile PINMASK_TYPE ign3_pin_mask;
volatile PORT_TYPE *ign4_pin_port;
volatile PINMAKS_TYPE ign4_pin_mask;
volatile PINMASK_TYPE ign4_pin_mask;
volatile PORT_TYPE *ign5_pin_port;
volatile PINMAKS_TYPE ign5_pin_mask;
volatile PINMASK_TYPE ign5_pin_mask;
volatile PORT_TYPE *ign6_pin_port;
volatile PINMAKS_TYPE ign6_pin_mask;
volatile PINMASK_TYPE ign6_pin_mask;
volatile PORT_TYPE *ign7_pin_port;
volatile PINMAKS_TYPE ign7_pin_mask;
volatile PINMASK_TYPE ign7_pin_mask;
volatile PORT_TYPE *ign8_pin_port;
volatile PINMAKS_TYPE ign8_pin_mask;
volatile PINMASK_TYPE ign8_pin_mask;
volatile PORT_TYPE *tach_pin_port;
volatile PINMAKS_TYPE tach_pin_mask;
volatile PINMASK_TYPE tach_pin_mask;
volatile PORT_TYPE *pump_pin_port;
volatile PINMAKS_TYPE pump_pin_mask;
volatile PINMASK_TYPE pump_pin_mask;
volatile PORT_TYPE *triggerPri_pin_port;
volatile PINMAKS_TYPE triggerPri_pin_mask;
volatile PINMASK_TYPE triggerPri_pin_mask;
volatile PORT_TYPE *triggerSec_pin_port;
volatile PINMAKS_TYPE triggerSec_pin_mask;
volatile PINMASK_TYPE triggerSec_pin_mask;
//These need to be here as they are used in both speeduino.ino and scheduler.ino
bool channel1InjEnabled = true;
@ -313,6 +313,7 @@ int ignition5EndAngle = 0;
//These are variables used across multiple files
bool initialisationComplete = false; //Tracks whether the setup() function has run completely
byte fpPrimeTime = 0; //The time (in seconds, based on currentStatus.secl) that the fuel pump started priming
volatile uint16_t mainLoopCount;
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)
volatile unsigned long timer5_overflow_count = 0; //Increments every time counter 5 overflows. Used for the fast version of micros()

View File

@ -42,9 +42,9 @@ unsigned int iacStepTime;
unsigned int completedHomeSteps;
volatile PORT_TYPE *idle_pin_port;
volatile PINMAKS_TYPE idle_pin_mask;
volatile PINMASK_TYPE idle_pin_mask;
volatile PORT_TYPE *idle2_pin_port;
volatile PINMAKS_TYPE idle2_pin_mask;
volatile PINMASK_TYPE idle2_pin_mask;
volatile bool idle_pwm_state;
unsigned int idle_pwm_max_count; //Used for variable PWM frequency

View File

@ -131,6 +131,15 @@ void initialiseAll()
endCoil3Charge();
endCoil4Charge();
endCoil5Charge();
#if (INJ_CHANNELS >= 6)
endCoil6Charge();
#endif
#if (INJ_CHANNELS >= 7)
endCoil7Charge();
#endif
#if (INJ_CHANNELS >= 8)
endCoil8Charge();
#endif
//Similar for injectors, make sure they're turned off
closeInjector1();
@ -138,6 +147,15 @@ void initialiseAll()
closeInjector3();
closeInjector4();
closeInjector5();
#if (IGN_CHANNELS >= 6)
closeInjector6();
#endif
#if (IGN_CHANNELS >= 7)
closeInjector7();
#endif
#if (IGN_CHANNELS >= 8)
closeInjector8();
#endif
//Set the tacho output default state
digitalWrite(pinTachOut, HIGH);
@ -225,6 +243,7 @@ void initialiseAll()
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
dwellLimit_uS = (1000 * configPage4.dwellLimit);
currentStatus.nChannels = (INJ_CHANNELS << 4) + IGN_CHANNELS; //First 4 bits store the number of injection channels, 2nd 4 store the number of ignition channels
fpPrimeTime = 0;
noInterrupts();
initialiseTriggers();
@ -754,7 +773,797 @@ void initialiseAll()
digitalWrite(LED_BUILTIN, HIGH);
}
void setPinMapping(byte boardID)
{
switch (boardID)
{
case 0:
#ifndef SMALL_FLASH_MODE //No support for bluepill here anyway
//Pin mappings as per the v0.1 shield
pinInjector1 = 8; //Output pin injector 1 is on
pinInjector2 = 9; //Output pin injector 2 is on
pinInjector3 = 11; //Output pin injector 3 is on
pinInjector4 = 10; //Output pin injector 4 is on
pinInjector5 = 12; //Output pin injector 5 is on
pinCoil1 = 6; //Pin for coil 1
pinCoil2 = 7; //Pin for coil 2
pinCoil3 = 12; //Pin for coil 3
pinCoil4 = 13; //Pin for coil 4
pinCoil5 = 14; //Pin for coil 5
pinTrigger = 2; //The CAS pin
pinTrigger2 = 3; //The CAS pin
pinTPS = A0; //TPS input pin
pinMAP = A1; //MAP sensor pin
pinIAT = A2; //IAT sensor pin
pinCLT = A3; //CLS sensor pin
pinO2 = A4; //O2 Sensor pin
pinIdle1 = 46; //Single wire idle control
pinIdle2 = 47; //2 wire idle control
pinStepperDir = 16; //Direction pin for DRV8825 driver
pinStepperStep = 17; //Step pin for DRV8825 driver
pinFan = 47; //Pin for the fan output
pinFuelPump = 4; //Fuel pump output
pinTachOut = 49; //Tacho output pin
pinFlex = 19; // Flex sensor (Must be external interrupt enabled)
pinResetControl = 43; //Reset control output
#endif
break;
case 1:
#ifndef SMALL_FLASH_MODE //No support for bluepill here anyway
//Pin mappings as per the v0.2 shield
pinInjector1 = 8; //Output pin injector 1 is on
pinInjector2 = 9; //Output pin injector 2 is on
pinInjector3 = 10; //Output pin injector 3 is on
pinInjector4 = 11; //Output pin injector 4 is on
pinInjector5 = 12; //Output pin injector 5 is on
pinCoil1 = 28; //Pin for coil 1
pinCoil2 = 24; //Pin for coil 2
pinCoil3 = 40; //Pin for coil 3
pinCoil4 = 36; //Pin for coil 4
pinCoil5 = 34; //Pin for coil 5 PLACEHOLDER value for now
pinTrigger = 20; //The CAS pin
pinTrigger2 = 21; //The Cam Sensor pin
pinTPS = A2; //TPS input pin
pinMAP = A3; //MAP sensor pin
pinIAT = A0; //IAT sensor pin
pinCLT = A1; //CLS sensor pin
pinO2 = A8; //O2 Sensor pin
pinBat = A4; //Battery reference voltage pin
pinDisplayReset = 48; // OLED reset pin
pinTachOut = 49; //Tacho output pin
pinIdle1 = 30; //Single wire idle control
pinIdle2 = 31; //2 wire idle control
pinStepperDir = 16; //Direction pin for DRV8825 driver
pinStepperStep = 17; //Step pin for DRV8825 driver
pinFan = 47; //Pin for the fan output
pinFuelPump = 4; //Fuel pump output
pinFlex = 2; // Flex sensor (Must be external interrupt enabled)
pinResetControl = 43; //Reset control output
break;
#endif
case 2:
#ifndef SMALL_FLASH_MODE //No support for bluepill here anyway
//Pin mappings as per the v0.3 shield
pinInjector1 = 8; //Output pin injector 1 is on
pinInjector2 = 9; //Output pin injector 2 is on
pinInjector3 = 10; //Output pin injector 3 is on
pinInjector4 = 11; //Output pin injector 4 is on
pinInjector5 = 12; //Output pin injector 5 is on
pinCoil1 = 28; //Pin for coil 1
pinCoil2 = 24; //Pin for coil 2
pinCoil3 = 40; //Pin for coil 3
pinCoil4 = 36; //Pin for coil 4
pinCoil5 = 34; //Pin for coil 5 PLACEHOLDER value for now
pinTrigger = 19; //The CAS pin
pinTrigger2 = 18; //The Cam Sensor pin
pinTPS = A2;//TPS input pin
pinMAP = A3; //MAP sensor pin
pinIAT = A0; //IAT sensor pin
pinCLT = A1; //CLS sensor pin
pinO2 = A8; //O2 Sensor pin
pinBat = A4; //Battery reference voltage pin
pinDisplayReset = 48; // OLED reset pin
pinTachOut = 49; //Tacho output pin
pinIdle1 = 5; //Single wire idle control
pinIdle2 = 53; //2 wire idle control
pinBoost = 7; //Boost control
pinVVT_1 = 6; //Default VVT output
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 = 51; //Can be overwritten below
pinFlex = 2; // Flex sensor (Must be external interrupt enabled)
pinResetControl = 50; //Reset control output
#if defined(CORE_TEENSY)
pinTrigger = 23;
pinStepperDir = 33;
pinStepperStep = 34;
pinCoil1 = 31;
pinTachOut = 28;
pinFan = 27;
pinCoil4 = 21;
pinCoil3 = 30;
pinO2 = A22;
#endif
#endif
break;
case 3:
//Pin mappings as per the v0.4 shield
pinInjector1 = 8; //Output pin injector 1 is on
pinInjector2 = 9; //Output pin injector 2 is on
pinInjector3 = 10; //Output pin injector 3 is on
pinInjector4 = 11; //Output pin injector 4 is on
pinInjector5 = 12; //Output pin injector 5 is on
pinInjector6 = 50; //CAUTION: Uses the same as Coil 4 below.
pinCoil1 = 40; //Pin for coil 1
pinCoil2 = 38; //Pin for coil 2
pinCoil3 = 52; //Pin for coil 3
pinCoil4 = 50; //Pin for coil 4
pinCoil5 = 34; //Pin for coil 5 PLACEHOLDER value for now
pinTrigger = 19; //The CAS pin
pinTrigger2 = 18; //The Cam Sensor pin
pinTPS = A2;//TPS input pin
pinMAP = A3; //MAP sensor pin
pinIAT = A0; //IAT sensor pin
pinCLT = A1; //CLS sensor pin
pinO2 = A8; //O2 Sensor pin
pinBat = A4; //Battery reference voltage pin
pinDisplayReset = 48; // OLED reset pin
pinTachOut = 49; //Tacho output pin (Goes to ULN2803)
pinIdle1 = 5; //Single wire idle control
pinIdle2 = 6; //2 wire idle control
pinBoost = 7; //Boost control
pinVVT_1 = 4; //Default VVT output
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 = 51; //Can be overwritten below
pinFlex = 2; // Flex sensor (Must be external interrupt enabled)
pinResetControl = 43; //Reset control output
#if defined(CORE_TEENSY)
pinInjector6 = 51;
pinTrigger = 23;
pinTrigger2 = 36;
pinStepperDir = 34;
pinStepperStep = 35;
pinCoil1 = 31;
pinCoil2 = 32;
pinTachOut = 28;
pinFan = 27;
pinCoil4 = 29;
pinCoil3 = 30;
pinO2 = A22;
#elif defined(STM32F4)
//Black F407VE http://wiki.stm32duino.com/index.php?title=STM32F407
//PC8~PC12 SDio
//PA13~PA15 & PB4 SWD(debug) pins
//PB0 EEPROM CS pin
//PA9 & PD10 Serial1
//PD5 & PD6 Serial2
pinInjector1 = PE7; //Output pin injector 1 is on
pinInjector2 = PE8; //Output pin injector 2 is on
pinInjector3 = PE9; //Output pin injector 3 is on
pinInjector4 = PE10; //Output pin injector 4 is on
pinInjector5 = PE11; //Output pin injector 5 is on
pinInjector6 = PE12; //Output pin injector 6 is on
pinCoil1 = PD0; //Pin for coil 1
pinCoil2 = PD1; //Pin for coil 2
pinCoil3 = PD2; //Pin for coil 3
pinCoil4 = PD3; //Pin for coil 4
pinCoil5 = PD4; //Pin for coil 5
pinTPS = A0; //TPS input pin
pinMAP = A1; //MAP sensor pin
pinIAT = A2; //IAT sensor pin
pinCLT = A3; //CLT sensor pin
pinO2 = A4; //O2 Sensor pin
pinBat = A5; //Battery reference voltage pin
pinBaro = A9;
pinIdle1 = PB8; //Single wire idle control
pinIdle2 = PB9; //2 wire idle control
pinBoost = PE0; //Boost control
pinVVT_1 = PE1; //Default VVT output
pinStepperDir = PD8; //Direction pin for DRV8825 driver
pinStepperStep = PB15; //Step pin for DRV8825 driver
pinStepperEnable = PD9; //Enable pin for DRV8825
pinDisplayReset = PE1; // OLED reset pin
pinFan = PE2; //Pin for the fan output
pinFuelPump = PC0; //Fuel pump output
pinTachOut = PC1; //Tacho output pin
//external interrupt enabled pins
//external interrupts could be enalbed in any pin, except same port numbers (PA4,PE4)
pinFlex = PE2; // Flex sensor (Must be external interrupt enabled)
pinTrigger = PE3; //The CAS pin
pinTrigger2 = PE4; //The Cam Sensor pin
#elif defined(CORE_STM32)
//blue pill http://wiki.stm32duino.com/index.php?title=Blue_Pill
//Maple mini http://wiki.stm32duino.com/index.php?title=Maple_Mini
//pins PA12, PA11 are used for USB or CAN couldn't be used for GPIO
pinInjector1 = PB7; //Output pin injector 1 is on
pinInjector2 = PB6; //Output pin injector 2 is on
pinInjector3 = PB5; //Output pin injector 3 is on
pinInjector4 = PB4; //Output pin injector 4 is on
pinCoil1 = PB3; //Pin for coil 1
pinCoil2 = PA15; //Pin for coil 2
pinCoil3 = PA14; //Pin for coil 3
pinCoil4 = PA9; //Pin for coil 4
pinCoil5 = PA8; //Pin for coil 5
pinTPS = A0; //TPS input pin
pinMAP = A1; //MAP sensor pin
pinIAT = A2; //IAT sensor pin
pinCLT = A3; //CLS sensor pin
pinO2 = A4; //O2 Sensor pin
pinBat = A5; //Battery reference voltage pin
pinBaro = pinMAP;
pinIdle1 = PB2; //Single wire idle control
pinIdle2 = PA2; //2 wire idle control
pinBoost = PA1; //Boost control
pinVVT_1 = PA0; //Default VVT output
pinStepperDir = PC15; //Direction pin for DRV8825 driver
pinStepperStep = PC14; //Step pin for DRV8825 driver
pinStepperEnable = PC13; //Enable pin for DRV8825
pinDisplayReset = PB2; // OLED reset pin
pinFan = PB1; //Pin for the fan output
pinFuelPump = PB11; //Fuel pump output
pinTachOut = PB10; //Tacho output pin
//external interrupt enabled pins
pinFlex = PB8; // Flex sensor (Must be external interrupt enabled)
pinTrigger = PA10; //The CAS pin
pinTrigger2 = PA13; //The Cam Sensor pin
#endif
break;
case 9:
//Pin mappings as per the MX5 PNP shield
pinInjector1 = 11; //Output pin injector 1 is on
pinInjector2 = 10; //Output pin injector 2 is on
pinInjector3 = 9; //Output pin injector 3 is on
pinInjector4 = 8; //Output pin injector 4 is on
pinInjector5 = 14; //Output pin injector 5 is on
pinCoil1 = 39; //Pin for coil 1
pinCoil2 = 41; //Pin for coil 2
pinCoil3 = 32; //Pin for coil 3
pinCoil4 = 33; //Pin for coil 4
pinCoil5 = 34; //Pin for coil 5 PLACEHOLDER value for now
pinTrigger = 19; //The CAS pin
pinTrigger2 = 18; //The Cam Sensor pin
pinTPS = A2;//TPS input pin
pinMAP = A5; //MAP sensor pin
pinIAT = A0; //IAT sensor pin
pinCLT = A1; //CLS sensor pin
pinO2 = A3; //O2 Sensor pin
pinBat = A4; //Battery reference voltage pin
pinDisplayReset = 48; // OLED reset pin
pinTachOut = 49; //Tacho output pin (Goes to ULN2803)
pinIdle1 = 2; //Single wire idle control
pinBoost = 4;
pinIdle2 = 4; //2 wire idle control (Note this is shared with boost!!!)
pinFuelPump = 37; //Fuel pump output
pinStepperDir = 16; //Direction pin for DRV8825 driver
pinStepperStep = 17; //Step pin for DRV8825 driver
pinFan = 35; //Pin for the fan output
pinLaunch = 12; //Can be overwritten below
pinFlex = 3; // Flex sensor (Must be external interrupt enabled)
pinResetControl = 44; //Reset control output
#if defined(CORE_TEENSY)
pinTrigger = 23;
pinTrigger2 = 36;
pinStepperDir = 34;
pinStepperStep = 35;
pinCoil1 = 33; //Done
pinCoil2 = 24; //Done
pinCoil3 = 51; //Won't work (No mapping for pin 32)
pinCoil4 = 52; //Won't work (No mapping for pin 33)
pinFuelPump = 26; //Requires PVT4 adapter or above
pinFan = 50; //Won't work (No mapping for pin 35)
pinTachOut = 28; //Done
#endif
break;
case 10:
#ifndef SMALL_FLASH_MODE //No support for bluepill here anyway
//Pin mappings for user turtanas PCB
pinInjector1 = 4; //Output pin injector 1 is on
pinInjector2 = 5; //Output pin injector 2 is on
pinInjector3 = 6; //Output pin injector 3 is on
pinInjector4 = 7; //Output pin injector 4 is on
pinInjector5 = 8; //Placeholder only - NOT USED
pinInjector6 = 9; //Placeholder only - NOT USED
pinInjector7 = 10; //Placeholder only - NOT USED
pinInjector8 = 11; //Placeholder only - NOT USED
pinCoil1 = 24; //Pin for coil 1
pinCoil2 = 28; //Pin for coil 2
pinCoil3 = 36; //Pin for coil 3
pinCoil4 = 40; //Pin for coil 4
pinCoil5 = 34; //Pin for coil 5 PLACEHOLDER value for now
pinTrigger = 18; //The CAS pin
pinTrigger2 = 19; //The Cam Sensor pin
pinTPS = A2;//TPS input pin
pinMAP = A3; //MAP sensor pin
pinMAP2 = A8; //MAP2 sensor pin
pinIAT = A0; //IAT sensor pin
pinCLT = A1; //CLS sensor pin
pinO2 = A4; //O2 Sensor pin
pinBat = A7; //Battery reference voltage pin
pinDisplayReset = 48; // OLED reset pin
pinSpareTemp1 = A6;
pinSpareTemp2 = A5;
pinTachOut = 41; //Tacho output pin transistori puuttuu 2n2222 tähän ja 1k 12v
pinFuelPump = 42; //Fuel pump output 2n2222
pinFan = 47; //Pin for the fan output
pinTachOut = 49; //Tacho output pin
pinFlex = 2; // Flex sensor (Must be external interrupt enabled)
pinResetControl = 26; //Reset control output
#endif
break;
case 20:
#ifndef SMALL_FLASH_MODE //No support for bluepill here anyway
//Pin mappings as per the Plazomat In/Out shields Rev 0.1
pinInjector1 = 8; //Output pin injector 1 is on
pinInjector2 = 9; //Output pin injector 2 is on
pinInjector3 = 10; //Output pin injector 3 is on
pinInjector4 = 11; //Output pin injector 4 is on
pinInjector5 = 12; //Output pin injector 5 is on
pinCoil1 = 28; //Pin for coil 1
pinCoil2 = 24; //Pin for coil 2
pinCoil3 = 40; //Pin for coil 3
pinCoil4 = 36; //Pin for coil 4
pinCoil5 = 34; //Pin for coil 5 PLACEHOLDER value for now
pinSpareOut1 = 4; //Spare LSD Output 1(PWM)
pinSpareOut2 = 5; //Spare LSD Output 2(PWM)
pinSpareOut3 = 6; //Spare LSD Output 3(PWM)
pinSpareOut4 = 7; //Spare LSD Output 4(PWM)
pinSpareOut5 = 50; //Spare LSD Output 5(digital)
pinSpareOut6 = 52; //Spare LSD Output 6(digital)
pinTrigger = 20; //The CAS pin
pinTrigger2 = 21; //The Cam Sensor pin
pinSpareTemp2 = A15; //spare Analog input 2
pinSpareTemp1 = A14; //spare Analog input 1
pinO2 = A8; //O2 Sensor pin
pinBat = A4; //Battery reference voltage pin
pinMAP = A3; //MAP sensor pin
pinTPS = A2;//TPS input pin
pinCLT = A1; //CLS sensor pin
pinIAT = A0; //IAT sensor pin
pinFan = 47; //Pin for the fan output
pinFuelPump = 4; //Fuel pump output
pinTachOut = 49; //Tacho output pin
pinResetControl = 26; //Reset control output
#endif
break;
case 30:
#ifndef SMALL_FLASH_MODE //No support for bluepill here anyway
//Pin mappings as per the dazv6 shield
pinInjector1 = 8; //Output pin injector 1 is on
pinInjector2 = 9; //Output pin injector 2 is on
pinInjector3 = 10; //Output pin injector 3 is on
pinInjector4 = 11; //Output pin injector 4 is on
pinInjector5 = 12; //Output pin injector 5 is on
pinCoil1 = 40; //Pin for coil 1
pinCoil2 = 38; //Pin for coil 2
pinCoil3 = 50; //Pin for coil 3
pinCoil4 = 52; //Pin for coil 4
pinCoil5 = 34; //Pin for coil 5 PLACEHOLDER value for now
pinTrigger = 19; //The CAS pin
pinTrigger2 = 18; //The Cam Sensor pin
pinTrigger3 = 17; // cam sensor 2 pin
pinTPS = A2;//TPS input pin
pinMAP = A3; //MAP sensor pin
pinIAT = A0; //IAT sensor pin
pinCLT = A1; //CLS sensor pin
pinO2 = A8; //O2 Sensor pin
pinO2_2 = A9; //O2 sensor pin (second sensor)
pinBat = A4; //Battery reference voltage pin
pinDisplayReset = 48; // OLED reset pin
pinTachOut = 49; //Tacho output pin
pinIdle1 = 5; //Single wire idle control
pinFuelPump = 45; //Fuel pump output
pinStepperDir = 20; //Direction pin for DRV8825 driver
pinStepperStep = 21; //Step pin for DRV8825 driver
pinSpareHOut1 = 4; // high current output spare1
pinSpareHOut2 = 6; // high current output spare2
pinBoost = 7;
pinSpareLOut1 = 43; //low current output spare1
pinSpareLOut2 = 47;
pinSpareLOut3 = 49;
pinSpareLOut4 = 51;
pinSpareLOut5 = 53;
pinFan = 47; //Pin for the fan output
#endif
break;
case 40:
//Pin mappings as per the NO2C shield
pinInjector1 = 8; //Output pin injector 1 is on
pinInjector2 = 9; //Output pin injector 2 is on
pinInjector3 = 11; //Output pin injector 3 is on - NOT USED
pinInjector4 = 12; //Output pin injector 4 is on - NOT USED
pinInjector5 = 13; //Placeholder only - NOT USED
pinCoil1 = 23; //Pin for coil 1
pinCoil2 = 22; //Pin for coil 2
pinCoil3 = 2; //Pin for coil 3 - ONLY WITH DB2
pinCoil4 = 3; //Pin for coil 4 - ONLY WITH DB2
pinCoil5 = 46; //Placeholder only - NOT USED
pinTrigger = 19; //The CAS pin
pinTrigger2 = 18; //The Cam Sensor pin
pinTPS = A3; //TPS input pin
pinMAP = A0; //MAP sensor pin
pinIAT = A5; //IAT sensor pin
pinCLT = A4; //CLT sensor pin
pinO2 = A2; //O2 sensor pin
pinBat = A1; //Battery reference voltage pin
pinBaro = A6; //Baro sensor pin - ONLY WITH DB
pinSpareTemp1 = A7; //spare Analog input 1 - ONLY WITH DB
pinDisplayReset = 48; // OLED reset pin - NOT USED
pinTachOut = 38; //Tacho output pin
pinIdle1 = 5; //Single wire idle control
pinIdle2 = 47; //2 wire idle control - NOT USED
pinBoost = 7; //Boost control
pinVVT_1 = 6; //Default VVT output
pinFuelPump = 4; //Fuel pump output
pinStepperDir = 25; //Direction pin for DRV8825 driver
pinStepperStep = 24; //Step pin for DRV8825 driver
pinStepperEnable = 27; //Enable pin for DRV8825 driver
pinLaunch = 10; //Can be overwritten below
pinFlex = 20; // Flex sensor (Must be external interrupt enabled) - ONLY WITH DB
pinFan = 30; //Pin for the fan output - ONLY WITH DB
pinSpareLOut1 = 32; //low current output spare1 - ONLY WITH DB
pinSpareLOut2 = 34; //low current output spare2 - ONLY WITH DB
pinSpareLOut3 = 36; //low current output spare3 - ONLY WITH DB
pinResetControl = 26; //Reset control output
break;
case 41:
#ifndef SMALL_FLASH_MODE //No support for bluepill here anyway
//Pin mappings as per the UA4C shield
pinInjector1 = 8; //Output pin injector 1 is on
pinInjector2 = 7; //Output pin injector 2 is on
pinInjector3 = 6; //Output pin injector 3 is on
pinInjector4 = 5; //Output pin injector 4 is on
pinInjector5 = 45; //Output pin injector 5 is on PLACEHOLDER value for now
pinCoil1 = 35; //Pin for coil 1
pinCoil2 = 36; //Pin for coil 2
pinCoil3 = 33; //Pin for coil 3
pinCoil4 = 34; //Pin for coil 4
pinCoil5 = 44; //Pin for coil 5 PLACEHOLDER value for now
pinTrigger = 19; //The CAS pin
pinTrigger2 = 18; //The Cam Sensor pin
pinFlex = 20; // Flex sensor
pinTPS = A3; //TPS input pin
pinMAP = A0; //MAP sensor pin
pinBaro = A7; //Baro sensor pin
pinIAT = A5; //IAT sensor pin
pinCLT = A4; //CLS sensor pin
pinO2 = A1; //O2 Sensor pin
pinO2_2 = A9; //O2 sensor pin (second sensor)
pinBat = A2; //Battery reference voltage pin
pinSpareTemp1 = A8; //spare Analog input 1
pinLaunch = 37; //Can be overwritten below
pinDisplayReset = 48; // OLED reset pin PLACEHOLDER value for now
pinTachOut = 22; //Tacho output pin
pinIdle1 = 9; //Single wire idle control
pinIdle2 = 10; //2 wire idle control
pinFuelPump = 23; //Fuel pump output
pinVVT_1 = 11; //Default VVT output
pinStepperDir = 32; //Direction pin for DRV8825 driver
pinStepperStep = 31; //Step pin for DRV8825 driver
pinStepperEnable = 30; //Enable pin for DRV8825 driver
pinBoost = 12; //Boost control
pinSpareLOut1 = 26; //low current output spare1
pinSpareLOut2 = 27; //low current output spare2
pinSpareLOut3 = 28; //low current output spare3
pinSpareLOut4 = 29; //low current output spare4
pinFan = 24; //Pin for the fan output
pinResetControl = 46; //Reset control output PLACEHOLDER value for now
#endif
break;
#if defined(CORE_TEENSY)
case 50:
//Pin mappings as per the teensy rev A shield
pinInjector1 = 2; //Output pin injector 1 is on
pinInjector2 = 10; //Output pin injector 2 is on
pinInjector3 = 6; //Output pin injector 3 is on
pinInjector4 = 9; //Output pin injector 4 is on
//Placeholder only - NOT USED:
//pinInjector5 = 13;
pinCoil1 = 29; //Pin for coil 1
pinCoil2 = 30; //Pin for coil 2
pinCoil3 = 31; //Pin for coil 3 - ONLY WITH DB2
pinCoil4 = 32; //Pin for coil 4 - ONLY WITH DB2
//Placeholder only - NOT USED:
//pinCoil5 = 46;
pinTrigger = 23; //The CAS pin
pinTrigger2 = 36; //The Cam Sensor pin
pinTPS = 16; //TPS input pin
pinMAP = 17; //MAP sensor pin
pinIAT = 14; //IAT sensor pin
pinCLT = 15; //CLT sensor pin
pinO2 = A22; //O2 sensor pin
pinO2_2 = A21; //O2 sensor pin (second sensor)
pinBat = 18; //Battery reference voltage pin
pinTachOut = 20; //Tacho output pin
pinIdle1 = 5; //Single wire idle control
pinBoost = 11; //Boost control
pinFuelPump = 38; //Fuel pump output
pinStepperDir = 34; //Direction pin for DRV8825 driver
pinStepperStep = 35; //Step pin for DRV8825 driver
pinStepperEnable = 33; //Enable pin for DRV8825 driver
pinLaunch = 26; //Can be overwritten below
pinFan = 37; //Pin for the fan output - ONLY WITH DB
pinSpareHOut1 = 8; // high current output spare1
pinSpareHOut2 = 7; // high current output spare2
pinSpareLOut1 = 21; //low current output spare1
break;
case 51:
//Pin mappings as per the teensy revB board shield
pinInjector1 = 2; //Output pin injector 1 is on
pinInjector2 = 10; //Output pin injector 2 is on
pinInjector3 = 6; //Output pin injector 3 is on - NOT USED
pinInjector4 = 9; //Output pin injector 4 is on - NOT USED
pinCoil1 = 29; //Pin for coil 1
pinCoil2 = 30; //Pin for coil 2
pinCoil3 = 31; //Pin for coil 3 - ONLY WITH DB2
pinCoil4 = 32; //Pin for coil 4 - ONLY WITH DB2
pinTrigger = 23; //The CAS pin
pinTrigger2 = 36; //The Cam Sensor pin
pinTPS = 16; //TPS input pin
pinMAP = 17; //MAP sensor pin
pinIAT = 14; //IAT sensor pin
pinCLT = 15; //CLT sensor pin
pinO2 = A22; //O2 sensor pin
pinO2_2 = A21; //O2 sensor pin (second sensor)
pinBat = 18; //Battery reference voltage pin
pinTachOut = 20; //Tacho output pin
pinIdle1 = 5; //Single wire idle control
pinBoost = 11; //Boost control
pinFuelPump = 38; //Fuel pump output
pinStepperDir = 34; //Direction pin for DRV8825 driver
pinStepperStep = 35; //Step pin for DRV8825 driver
pinStepperEnable = 33; //Enable pin for DRV8825 driver
pinLaunch = 26; //Can be overwritten below
pinFan = 37; //Pin for the fan output - ONLY WITH DB
pinSpareHOut1 = 8; // high current output spare1
pinSpareHOut2 = 7; // high current output spare2
pinSpareLOut1 = 21; //low current output spare1
break;
#endif
default:
#if defined(STM32F4)
//Black F407VE http://wiki.stm32duino.com/index.php?title=STM32F407
//PC8~PC12 SDio
//PA13~PA15 & PB4 SWD(debug) pins
//PB0 EEPROM CS pin
//PA9 & PD10 Serial1
//PD5 & PD6 Serial2
pinInjector1 = PE7; //Output pin injector 1 is on
pinInjector2 = PE8; //Output pin injector 2 is on
pinInjector3 = PE9; //Output pin injector 3 is on
pinInjector4 = PE10; //Output pin injector 4 is on
pinInjector5 = PE11; //Output pin injector 5 is on
pinInjector6 = PE12; //Output pin injector 6 is on
pinCoil1 = PD0; //Pin for coil 1
pinCoil2 = PD1; //Pin for coil 2
pinCoil3 = PD2; //Pin for coil 3
pinCoil4 = PD3; //Pin for coil 4
pinCoil5 = PD4; //Pin for coil 5
pinTPS = A0; //TPS input pin
pinMAP = A1; //MAP sensor pin
pinIAT = A2; //IAT sensor pin
pinCLT = A3; //CLT sensor pin
pinO2 = A4; //O2 Sensor pin
pinBat = A5; //Battery reference voltage pin
pinBaro = A9;
pinIdle1 = PB8; //Single wire idle control
pinIdle2 = PB9; //2 wire idle control
pinBoost = PE0; //Boost control
pinVVT_1 = PE1; //Default VVT output
pinStepperDir = PD8; //Direction pin for DRV8825 driver
pinStepperStep = PB15; //Step pin for DRV8825 driver
pinStepperEnable = PD9; //Enable pin for DRV8825
pinDisplayReset = PE1; // OLED reset pin
pinFan = PE2; //Pin for the fan output
pinFuelPump = PC0; //Fuel pump output
pinTachOut = PC1; //Tacho output pin
//external interrupt enabled pins
//external interrupts could be enalbed in any pin, except same port numbers (PA4,PE4)
pinFlex = PE2; // Flex sensor (Must be external interrupt enabled)
pinTrigger = PE3; //The CAS pin
pinTrigger2 = PE4; //The Cam Sensor pin
#else
#ifndef SMALL_FLASH_MODE //No support for bluepill here anyway
//Pin mappings as per the v0.2 shield
pinInjector1 = 8; //Output pin injector 1 is on
pinInjector2 = 9; //Output pin injector 2 is on
pinInjector3 = 10; //Output pin injector 3 is on
pinInjector4 = 11; //Output pin injector 4 is on
pinInjector5 = 12; //Output pin injector 5 is on
pinCoil1 = 28; //Pin for coil 1
pinCoil2 = 24; //Pin for coil 2
pinCoil3 = 40; //Pin for coil 3
pinCoil4 = 36; //Pin for coil 4
pinCoil5 = 34; //Pin for coil 5 PLACEHOLDER value for now
pinTrigger = 20; //The CAS pin
pinTrigger2 = 21; //The Cam Sensor pin
pinTPS = A2; //TPS input pin
pinMAP = A3; //MAP sensor pin
pinIAT = A0; //IAT sensor pin
pinCLT = A1; //CLS sensor pin
pinO2 = A8; //O2 Sensor pin
pinBat = A4; //Battery reference voltage pin
pinStepperDir = 16; //Direction pin for DRV8825 driver
pinStepperStep = 17; //Step pin for DRV8825 driver
pinDisplayReset = 48; // OLED reset pin
pinFan = 47; //Pin for the fan output
pinFuelPump = 4; //Fuel pump output
pinTachOut = 49; //Tacho output pin
pinFlex = 3; // Flex sensor (Must be external interrupt enabled)
pinBoost = 5;
pinIdle1 = 6;
pinResetControl = 43; //Reset control output
#endif
#endif
break;
}
//Setup any devices that are using selectable pins
if ( (configPage6.launchPin != 0) && (configPage6.launchPin < BOARD_NR_GPIO_PINS) ) { pinLaunch = pinTranslate(configPage6.launchPin); }
if ( (configPage4.ignBypassPin != 0) && (configPage4.ignBypassPin < BOARD_NR_GPIO_PINS) ) { pinIgnBypass = pinTranslate(configPage4.ignBypassPin); }
if ( (configPage2.tachoPin != 0) && (configPage2.tachoPin < BOARD_NR_GPIO_PINS) ) { pinTachOut = pinTranslate(configPage2.tachoPin); }
if ( (configPage4.fuelPumpPin != 0) && (configPage4.fuelPumpPin < BOARD_NR_GPIO_PINS) ) { pinFuelPump = pinTranslate(configPage4.fuelPumpPin); }
if ( (configPage6.fanPin != 0) && (configPage6.fanPin < BOARD_NR_GPIO_PINS) ) { pinFan = pinTranslate(configPage6.fanPin); }
if ( (configPage6.boostPin != 0) && (configPage6.boostPin < BOARD_NR_GPIO_PINS) ) { pinBoost = pinTranslate(configPage6.boostPin); }
if ( (configPage6.vvtPin != 0) && (configPage6.vvtPin < BOARD_NR_GPIO_PINS) ) { pinVVT_1 = pinTranslate(configPage6.vvtPin); }
if ( (configPage6.useExtBaro != 0) && (configPage6.baroPin < BOARD_NR_GPIO_PINS) ) { pinBaro = configPage6.baroPin + A0; }
if ( (configPage6.useEMAP != 0) && (configPage10.EMAPPin < BOARD_NR_GPIO_PINS) ) { pinEMAP = configPage10.EMAPPin + A0; }
//Currently there's no default pin for Idle Up
pinIdleUp = pinTranslate(configPage2.idleUpPin);
/* Reset control is a special case. If reset control is enabled, it needs its initial state set BEFORE its pinMode.
If that doesn't happen and reset control is in "Serial Command" mode, the Arduino will end up in a reset loop
because the control pin will go low as soon as the pinMode is set to OUTPUT. */
if ( (configPage4.resetControl != 0) && (configPage4.resetControlPin < BOARD_NR_GPIO_PINS) )
{
resetControl = configPage4.resetControl;
pinResetControl = pinTranslate(configPage4.resetControlPin);
setResetControlPinState();
pinMode(pinResetControl, OUTPUT);
}
//Finally, set the relevant pin modes for outputs
pinMode(pinCoil1, OUTPUT);
pinMode(pinCoil2, OUTPUT);
pinMode(pinCoil3, OUTPUT);
pinMode(pinCoil4, OUTPUT);
pinMode(pinCoil5, OUTPUT);
pinMode(pinInjector1, OUTPUT);
pinMode(pinInjector2, OUTPUT);
pinMode(pinInjector3, OUTPUT);
pinMode(pinInjector4, OUTPUT);
pinMode(pinInjector5, OUTPUT);
pinMode(pinTachOut, OUTPUT);
pinMode(pinIdle1, OUTPUT);
pinMode(pinIdle2, OUTPUT);
pinMode(pinFuelPump, OUTPUT);
pinMode(pinIgnBypass, OUTPUT);
pinMode(pinFan, OUTPUT);
pinMode(pinStepperDir, OUTPUT);
pinMode(pinStepperStep, OUTPUT);
pinMode(pinStepperEnable, OUTPUT);
pinMode(pinBoost, OUTPUT);
pinMode(pinVVT_1, OUTPUT);
inj1_pin_port = portOutputRegister(digitalPinToPort(pinInjector1));
inj1_pin_mask = digitalPinToBitMask(pinInjector1);
inj2_pin_port = portOutputRegister(digitalPinToPort(pinInjector2));
inj2_pin_mask = digitalPinToBitMask(pinInjector2);
inj3_pin_port = portOutputRegister(digitalPinToPort(pinInjector3));
inj3_pin_mask = digitalPinToBitMask(pinInjector3);
inj4_pin_port = portOutputRegister(digitalPinToPort(pinInjector4));
inj4_pin_mask = digitalPinToBitMask(pinInjector4);
inj5_pin_port = portOutputRegister(digitalPinToPort(pinInjector5));
inj5_pin_mask = digitalPinToBitMask(pinInjector5);
inj6_pin_port = portOutputRegister(digitalPinToPort(pinInjector6));
inj6_pin_mask = digitalPinToBitMask(pinInjector6);
inj7_pin_port = portOutputRegister(digitalPinToPort(pinInjector7));
inj7_pin_mask = digitalPinToBitMask(pinInjector7);
inj8_pin_port = portOutputRegister(digitalPinToPort(pinInjector8));
inj8_pin_mask = digitalPinToBitMask(pinInjector8);
ign1_pin_port = portOutputRegister(digitalPinToPort(pinCoil1));
ign1_pin_mask = digitalPinToBitMask(pinCoil1);
ign2_pin_port = portOutputRegister(digitalPinToPort(pinCoil2));
ign2_pin_mask = digitalPinToBitMask(pinCoil2);
ign3_pin_port = portOutputRegister(digitalPinToPort(pinCoil3));
ign3_pin_mask = digitalPinToBitMask(pinCoil3);
ign4_pin_port = portOutputRegister(digitalPinToPort(pinCoil4));
ign4_pin_mask = digitalPinToBitMask(pinCoil4);
ign5_pin_port = portOutputRegister(digitalPinToPort(pinCoil5));
ign5_pin_mask = digitalPinToBitMask(pinCoil5);
ign6_pin_port = portOutputRegister(digitalPinToPort(pinCoil6));
ign6_pin_mask = digitalPinToBitMask(pinCoil6);
ign7_pin_port = portOutputRegister(digitalPinToPort(pinCoil7));
ign7_pin_mask = digitalPinToBitMask(pinCoil7);
ign8_pin_port = portOutputRegister(digitalPinToPort(pinCoil8));
ign8_pin_mask = digitalPinToBitMask(pinCoil8);
tach_pin_port = portOutputRegister(digitalPinToPort(pinTachOut));
tach_pin_mask = digitalPinToBitMask(pinTachOut);
pump_pin_port = portOutputRegister(digitalPinToPort(pinFuelPump));
pump_pin_mask = digitalPinToBitMask(pinFuelPump);
//And for inputs
#if defined(CORE_STM32)
#ifndef ARDUINO_ARCH_STM32 //libmaple core aka STM32DUINO
pinMode(pinMAP, INPUT_ANALOG);
pinMode(pinO2, INPUT_ANALOG);
pinMode(pinO2_2, INPUT_ANALOG);
pinMode(pinTPS, INPUT_ANALOG);
pinMode(pinIAT, INPUT_ANALOG);
pinMode(pinCLT, INPUT_ANALOG);
pinMode(pinBat, INPUT_ANALOG);
pinMode(pinBaro, INPUT_ANALOG);
#else
pinMode(pinMAP, INPUT);
pinMode(pinO2, INPUT);
pinMode(pinO2_2, INPUT);
pinMode(pinTPS, INPUT);
pinMode(pinIAT, INPUT);
pinMode(pinCLT, INPUT);
pinMode(pinBat, INPUT);
pinMode(pinBaro, INPUT);
#endif
#endif
pinMode(pinTrigger, INPUT);
pinMode(pinTrigger2, INPUT);
pinMode(pinTrigger3, INPUT);
//Each of the below are only set when their relevant function is enabled. This can help prevent pin conflicts that users aren't aware of with unused functions
if(configPage2.flexEnabled > 0)
{
pinMode(pinFlex, INPUT); //Standard GM / Continental flex sensor requires pullup, but this should be onboard. The internal pullup will not work (Requires ~3.3k)!
}
if(configPage6.launchEnabled > 0)
{
if (configPage6.lnchPullRes == true) { pinMode(pinLaunch, INPUT_PULLUP); }
else { pinMode(pinLaunch, INPUT); } //If Launch Pull Resistor is not set make input float.
}
if(configPage2.idleUpEnabled > 0)
{
if (configPage2.idleUpPolarity == 0) { pinMode(pinIdleUp, INPUT_PULLUP); } //Normal setting
else { pinMode(pinIdleUp, INPUT); } //inverted setting
}
//These must come after the above pinMode statements
triggerPri_pin_port = portInputRegister(digitalPinToPort(pinTrigger));
triggerPri_pin_mask = digitalPinToBitMask(pinTrigger);
triggerSec_pin_port = portInputRegister(digitalPinToPort(pinTrigger2));
triggerSec_pin_mask = digitalPinToBitMask(pinTrigger2);
#if defined(CORE_STM32)
#else
//Set default values
digitalWrite(pinMAP, HIGH);
//digitalWrite(pinO2, LOW);
digitalWrite(pinTPS, LOW);
#endif
}
void initialiseTriggers()
{

View File

@ -64,20 +64,28 @@ void initialiseSchedulers()
fuelSchedule8.schedulesSet = 0;
fuelSchedule1.counter = &FUEL1_COUNTER;
fuelSchedule1.compare = &FUEL1_COMPARE;
fuelSchedule2.counter = &FUEL2_COUNTER;
fuelSchedule2.compare = &FUEL2_COMPARE;
fuelSchedule3.counter = &FUEL3_COUNTER;
fuelSchedule3.compare = &FUEL3_COMPARE;
fuelSchedule4.counter = &FUEL4_COUNTER;
fuelSchedule4.compare = &FUEL4_COMPARE;
#if (INJ_CHANNELS >= 5)
fuelSchedule5.counter = &FUEL5_COUNTER;
fuelSchedule5.compare = &FUEL5_COMPARE;
#endif
#if (INJ_CHANNELS >= 6)
fuelSchedule5.counter = &FUEL6_COUNTER;
fuelSchedule6.counter = &FUEL6_COUNTER;
fuelSchedule6.compare = &FUEL6_COMPARE;
#endif
#if (INJ_CHANNELS >= 7)
fuelSchedule5.counter = &FUEL7_COUNTER;
fuelSchedule7.counter = &FUEL7_COUNTER;
fuelSchedule7.compare = &FUEL7_COMPARE;
#endif
#if (INJ_CHANNELS >= 8)
fuelSchedule5.counter = &FUEL8_COUNTER;
fuelSchedule8.counter = &FUEL8_COUNTER;
fuelSchedule8.compare = &FUEL8_COMPARE;
#endif
ignitionSchedule1.Status = OFF;
@ -98,6 +106,31 @@ void initialiseSchedulers()
ignitionSchedule7.schedulesSet = 0;
ignitionSchedule8.schedulesSet = 0;
ignitionSchedule1.counter = &IGN1_COUNTER;
ignitionSchedule1.compare = &IGN1_COMPARE;
ignitionSchedule2.counter = &IGN2_COUNTER;
ignitionSchedule2.compare = &IGN2_COMPARE;
ignitionSchedule3.counter = &IGN3_COUNTER;
ignitionSchedule3.compare = &IGN3_COMPARE;
ignitionSchedule4.counter = &IGN4_COUNTER;
ignitionSchedule4.compare = &IGN4_COMPARE;
#if (INJ_CHANNELS >= 5)
ignitionSchedule5.counter = &IGN5_COUNTER;
ignitionSchedule5.compare = &IGN5_COMPARE;
#endif
#if (INJ_CHANNELS >= 6)
ignitionSchedule6.counter = &IGN6_COUNTER;
ignitionSchedule6.compare = &IGN6_COMPARE;
#endif
#if (INJ_CHANNELS >= 7)
ignitionSchedule7.counter = &IGN7_COUNTER;
ignitionSchedule7.compare = &IGN7_COMPARE;
#endif
#if (INJ_CHANNELS >= 8)
ignitionSchedule8.counter = &IGN8_COUNTER;
ignitionSchedule8.compare = &IGN8_COMPARE;
#endif
}
/*

View File

@ -9,6 +9,7 @@ A full copy of the license may be found in the projects root directory
#include "maths.h"
#include "storage.h"
#include "comms.h"
#include "idle.h"
void initialiseADC()
{
@ -375,6 +376,24 @@ void readBat()
tempReading = analogRead(pinBat);
tempReading = fastMap1023toX(analogRead(pinBat), 245); //Get the current raw Battery value. Permissible values are from 0v to 24.5v (245)
#endif
//The following is a check for if the voltage has jumped up from under 5.5v to over 7v.
//If this occurs, it's very likely that the system has gone from being powered by USB to being powered from the 12v power source.
//Should that happen, we retrigger the fuel pump priming and idle homing (If using a stepper)
if( (currentStatus.battery10 < 55) && (tempReading > 70) && (currentStatus.RPM == 0) )
{
//Reprime the fuel pump
fpPrimeTime = currentStatus.secl;
fpPrimed = false;
FUEL_PUMP_ON();
//Redo the stepper homing
if( (configPage6.iacAlgorithm == IAC_ALGORITHM_STEP_CL) || (configPage6.iacAlgorithm == IAC_ALGORITHM_STEP_OL) )
{
initialiseIdle();
}
}
currentStatus.battery10 = ADC_FILTER(tempReading, configPage4.ADCFILTER_BAT, currentStatus.battery10);
}

View File

@ -12,6 +12,8 @@ A full copy of the license may be found in the projects root directory
#include "src/FlashStorage/FlashAsEEPROM.h"
#elif defined(ARDUINO_BLACK_F407VE)
#include "src/BackupSram/BackupSramAsEEPROM.h"
#elif defined(CORE_STM32)
#include <Fram.h>
#else
#include <EEPROM.h>
#endif
@ -19,16 +21,16 @@ A full copy of the license may be found in the projects root directory
void writeAllConfig()
{
writeConfig(1);
if (eepromWritesPending == false) { writeConfig(2); }
if (eepromWritesPending == false) { writeConfig(3); }
if (eepromWritesPending == false) { writeConfig(4); }
if (eepromWritesPending == false) { writeConfig(5); }
if (eepromWritesPending == false) { writeConfig(6); }
if (eepromWritesPending == false) { writeConfig(7); }
if (eepromWritesPending == false) { writeConfig(8); }
if (eepromWritesPending == false) { writeConfig(9); }
if (eepromWritesPending == false) { writeConfig(10); }
writeConfig(veSetPage);
if (eepromWritesPending == false) { writeConfig(veMapPage); }
if (eepromWritesPending == false) { writeConfig(ignMapPage); }
if (eepromWritesPending == false) { writeConfig(ignSetPage); }
if (eepromWritesPending == false) { writeConfig(afrMapPage); }
if (eepromWritesPending == false) { writeConfig(afrSetPage); }
if (eepromWritesPending == false) { writeConfig(boostvvtPage); }
if (eepromWritesPending == false) { writeConfig(seqFuelPage); }
if (eepromWritesPending == false) { writeConfig(canbusPage); }
if (eepromWritesPending == false) { writeConfig(warmupPage); }
}

View File

@ -95,7 +95,7 @@ void oneMSInterval() //Most ARM chips can simply call a function
{
loop250ms = 0; //Reset Counter
BIT_SET(TIMER_mask, BIT_TIMER_4HZ);
#if defined(CORE_STM32) //debug purpose, only visal for running code
#if defined(CORE_STM32) //debug purpose, only visual for running code
digitalWrite(LED_BUILTIN, !digitalRead(LED_BUILTIN));
#endif
@ -143,7 +143,8 @@ void oneMSInterval() //Most ARM chips can simply call a function
//Check whether fuel pump priming is complete
if(fpPrimed == false)
{
if(currentStatus.secl >= configPage2.fpPrime)
//fpPrimeTime is the time that the pump priming started. This is 0 on startup, but can be changed if the unit has been running on USB power and then had the ignition turned on (Which starts the priming again)
if( (currentStatus.secl - fpPrimeTime) >= configPage2.fpPrime)
{
fpPrimed = true; //Mark the priming as being completed
if(currentStatus.RPM == 0)

View File

@ -10,6 +10,8 @@
#include "src/FlashStorage/FlashAsEEPROM.h"
#elif defined(ARDUINO_BLACK_F407VE)
#include "src/BackupSram/BackupSramAsEEPROM.h"
#elif defined(CORE_STM32)
#include <Fram.h>
#else
#include <EEPROM.h>
#endif