Merge pull request #204 from Tjeerdie/dev_stm32F407VE

Dev stm32 f407 ve
This commit is contained in:
Josh Stewart 2019-03-04 09:35:59 +11:00 committed by GitHub
commit 0dce5ebb9b
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
16 changed files with 3709 additions and 8 deletions

BIN
Screenshot_TS_stm32F407.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 365 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 37 KiB

View File

@ -77,5 +77,526 @@ static inline unsigned long micros_safe()
return newMicros; return newMicros;
} }
#endif #endif
void setPinMapping(byte boardID)
{
switch (boardID)
{
case 0:
//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
break;
case 1:
//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;
case 2:
//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
break;
#endif 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
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
break;
case 10:
//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
break;
case 20:
//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
break;
case 30:
//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
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:
//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
break;
default:
//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
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);
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);
//Set default values
digitalWrite(pinMAP, HIGH);
//digitalWrite(pinO2, LOW);
digitalWrite(pinTPS, LOW);
}
#endif

View File

@ -1,4 +1,4 @@
#if defined(CORE_STM32) #if defined(CORE_STM32) && !defined(ARDUINO_BLACK_F407VE)
#include "board_stm32.h" #include "board_stm32.h"
#include "globals.h" #include "globals.h"
#include "auxiliaries.h" #include "auxiliaries.h"
@ -162,5 +162,735 @@ uint16_t freeRam()
char top = 't'; char top = 't';
return &top - reinterpret_cast<char*>(sbrk(0)); return &top - reinterpret_cast<char*>(sbrk(0));
} }
//pinmapping the STM32F407 for different boards, at this moment no board is desgined.
//All boards are set to the default just to be sure.
void setPinMapping(byte boardID)
{
switch (boardID)
{
case 0:
//Pin mappings as per the v0.4 shield
//Black F407VE http://wiki.stm32duino.com/index.php?title=STM32F407
//PC8~PC12 SDio
//PA9..PA10 Serial1
//PA11..PA12 USB
//PA13..PA15 & PB4 SWD(debug) pins
//PB0 EEPROM CS pin
//PB1 LCD
//PB2 BOOT1
//PB3..PB5 SPI interface
//PB6..PB8 NRF interface
//PD5 & PD6 Serial2
pinInjector1 = PA1; //Output pin injector 1 is on
pinInjector2 = PA2; //Output pin injector 2 is on
pinInjector3 = PA3; //Output pin injector 3 is on
pinInjector4 = PA4; //Output pin injector 4 is on
pinInjector5 = PA5; //Output pin injector 5 is on
pinInjector6 = PD4; //Output pin injector 6 is on
pinCoil1 = PD7; //Pin for coil 1
pinCoil2 = PB9; //Pin for coil 2
pinCoil3 = PA8; //Pin for coil 3
pinCoil4 = PB10; //Pin for coil 4
pinCoil5 = PB11; //Pin for coil 5
pinMAP = PC0; //MAP sensor pin
pinTPS = PC1;//TPS input pin
pinIAT = PC2; //IAT sensor pin
pinCLT = PC3; //CLS sensor pin
pinO2 = PC5; //O2 Sensor pin
pinBat = PB1; //Battery reference voltage pin
pinBaro = PC4;
pinIdle1 = PB12; //Single wire idle control
pinIdle2 = PB11; //2 wire idle control
pinBoost = PC7; //Boost control
pinVVT_1 = PD3; //Default VVT output
pinStepperDir = PE0; //Direction pin for DRV8825 driver
pinStepperStep = PE1; //Step pin for DRV8825 driver
pinStepperEnable = PE2; //Enable pin for DRV8825
pinDisplayReset = PE5; // OLED reset pin
pinFan = PE6; //Pin for the fan output
pinFuelPump = PA6; //Fuel pump output
pinTachOut = PD15; //Tacho output pin
// pinLaunch = 51; //Can be overwritten below
// pinResetControl = 43; //Reset control output
//external interrupt enabled pins
//external interrupts could be enalbed in any pin, except same port numbers (PA4,PE4)
pinFlex = PD4; // Flex sensor (Must be external interrupt enabled)
pinTrigger = PD13; //The CAS pin
pinTrigger2 = PD14; //The Cam Sensor pin
break;
case 1:
//Pin mappings as per the v0.4 shield
//Black F407VE http://wiki.stm32duino.com/index.php?title=STM32F407
//PC8~PC12 SDio
//PA9..PA10 Serial1
//PA11..PA12 USB
//PA13..PA15 & PB4 SWD(debug) pins
//PB0 EEPROM CS pin
//PB1 LCD
//PB2 BOOT1
//PB3..PB5 SPI interface
//PB6..PB8 NRF interface
//PD5 & PD6 Serial2
pinInjector1 = PA1; //Output pin injector 1 is on
pinInjector2 = PA2; //Output pin injector 2 is on
pinInjector3 = PA3; //Output pin injector 3 is on
pinInjector4 = PA4; //Output pin injector 4 is on
pinInjector5 = PA5; //Output pin injector 5 is on
pinInjector6 = PD4; //Output pin injector 6 is on
pinCoil1 = PD7; //Pin for coil 1
pinCoil2 = PB9; //Pin for coil 2
pinCoil3 = PA8; //Pin for coil 3
pinCoil4 = PB10; //Pin for coil 4
pinCoil5 = PB11; //Pin for coil 5
pinMAP = PC0; //MAP sensor pin
pinTPS = PC1;//TPS input pin
pinIAT = PC2; //IAT sensor pin
pinCLT = PC3; //CLS sensor pin
pinO2 = PC5; //O2 Sensor pin
pinBat = PB1; //Battery reference voltage pin
pinBaro = PC4;
pinIdle1 = PB12; //Single wire idle control
pinIdle2 = PB11; //2 wire idle control
pinBoost = PC7; //Boost control
pinVVT_1 = PD3; //Default VVT output
pinStepperDir = PE0; //Direction pin for DRV8825 driver
pinStepperStep = PE1; //Step pin for DRV8825 driver
pinStepperEnable = PE2; //Enable pin for DRV8825
pinDisplayReset = PE5; // OLED reset pin
pinFan = PE6; //Pin for the fan output
pinFuelPump = PA6; //Fuel pump output
pinTachOut = PD15; //Tacho output pin
// pinLaunch = 51; //Can be overwritten below
// pinResetControl = 43; //Reset control output
//external interrupt enabled pins
//external interrupts could be enalbed in any pin, except same port numbers (PA4,PE4)
pinFlex = PD4; // Flex sensor (Must be external interrupt enabled)
pinTrigger = PD13; //The CAS pin
pinTrigger2 = PD14; //The Cam Sensor pin
break;
case 2:
//Pin mappings as per the v0.4 shield
//Black F407VE http://wiki.stm32duino.com/index.php?title=STM32F407
//PC8~PC12 SDio
//PA9..PA10 Serial1
//PA11..PA12 USB
//PA13..PA15 & PB4 SWD(debug) pins
//PB0 EEPROM CS pin
//PB1 LCD
//PB2 BOOT1
//PB3..PB5 SPI interface
//PB6..PB8 NRF interface
//PD5 & PD6 Serial2
pinInjector1 = PA1; //Output pin injector 1 is on
pinInjector2 = PA2; //Output pin injector 2 is on
pinInjector3 = PA3; //Output pin injector 3 is on
pinInjector4 = PA4; //Output pin injector 4 is on
pinInjector5 = PA5; //Output pin injector 5 is on
pinInjector6 = PD4; //Output pin injector 6 is on
pinCoil1 = PD7; //Pin for coil 1
pinCoil2 = PB9; //Pin for coil 2
pinCoil3 = PA8; //Pin for coil 3
pinCoil4 = PB10; //Pin for coil 4
pinCoil5 = PB11; //Pin for coil 5
pinMAP = PC0; //MAP sensor pin
pinTPS = PC1;//TPS input pin
pinIAT = PC2; //IAT sensor pin
pinCLT = PC3; //CLS sensor pin
pinO2 = PC5; //O2 Sensor pin
pinBat = PB1; //Battery reference voltage pin
pinBaro = PC4;
pinIdle1 = PB12; //Single wire idle control
pinIdle2 = PB11; //2 wire idle control
pinBoost = PC7; //Boost control
pinVVT_1 = PD3; //Default VVT output
pinStepperDir = PE0; //Direction pin for DRV8825 driver
pinStepperStep = PE1; //Step pin for DRV8825 driver
pinStepperEnable = PE2; //Enable pin for DRV8825
pinDisplayReset = PE5; // OLED reset pin
pinFan = PE6; //Pin for the fan output
pinFuelPump = PA6; //Fuel pump output
pinTachOut = PD15; //Tacho output pin
// pinLaunch = 51; //Can be overwritten below
// pinResetControl = 43; //Reset control output
//external interrupt enabled pins
//external interrupts could be enalbed in any pin, except same port numbers (PA4,PE4)
pinFlex = PD4; // Flex sensor (Must be external interrupt enabled)
pinTrigger = PD13; //The CAS pin
pinTrigger2 = PD14; //The Cam Sensor pin
break;
case 3:
//Pin mappings as per the v0.4 shield
//Black F407VE http://wiki.stm32duino.com/index.php?title=STM32F407
//PC8~PC12 SDio
//PA9..PA10 Serial1
//PA11..PA12 USB
//PA13..PA15 & PB4 SWD(debug) pins
//PB0 EEPROM CS pin
//PB1 LCD
//PB2 BOOT1
//PB3..PB5 SPI interface
//PB6..PB8 NRF interface
//PD5 & PD6 Serial2
pinInjector1 = PA1; //Output pin injector 1 is on
pinInjector2 = PA2; //Output pin injector 2 is on
pinInjector3 = PA3; //Output pin injector 3 is on
pinInjector4 = PA4; //Output pin injector 4 is on
pinInjector5 = PA5; //Output pin injector 5 is on
pinInjector6 = PD4; //Output pin injector 6 is on
pinCoil1 = PD7; //Pin for coil 1
pinCoil2 = PB9; //Pin for coil 2
pinCoil3 = PA8; //Pin for coil 3
pinCoil4 = PB10; //Pin for coil 4
pinCoil5 = PB11; //Pin for coil 5
pinMAP = PC0; //MAP sensor pin
pinTPS = PC1;//TPS input pin
pinIAT = PC2; //IAT sensor pin
pinCLT = PC3; //CLS sensor pin
pinO2 = PC5; //O2 Sensor pin
pinBat = PB1; //Battery reference voltage pin
pinBaro = PC4;
pinIdle1 = PB12; //Single wire idle control
pinIdle2 = PB11; //2 wire idle control
pinBoost = PC7; //Boost control
pinVVT_1 = PD3; //Default VVT output
pinStepperDir = PE0; //Direction pin for DRV8825 driver
pinStepperStep = PE1; //Step pin for DRV8825 driver
pinStepperEnable = PE2; //Enable pin for DRV8825
pinDisplayReset = PE5; // OLED reset pin
pinFan = PE6; //Pin for the fan output
pinFuelPump = PA6; //Fuel pump output
pinTachOut = PD15; //Tacho output pin
// pinLaunch = 51; //Can be overwritten below
// pinResetControl = 43; //Reset control output
//external interrupt enabled pins
//external interrupts could be enalbed in any pin, except same port numbers (PA4,PE4)
pinFlex = PD4; // Flex sensor (Must be external interrupt enabled)
pinTrigger = PD13; //The CAS pin
pinTrigger2 = PD14; //The Cam Sensor pin
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
break;
case 10:
//Pin mappings as per the v0.4 shield
//Black F407VE http://wiki.stm32duino.com/index.php?title=STM32F407
//PC8~PC12 SDio
//PA9..PA10 Serial1
//PA11..PA12 USB
//PA13..PA15 & PB4 SWD(debug) pins
//PB0 EEPROM CS pin
//PB1 LCD
//PB2 BOOT1
//PB3..PB5 SPI interface
//PB6..PB8 NRF interface
//PD5 & PD6 Serial2
pinInjector1 = PA1; //Output pin injector 1 is on
pinInjector2 = PA2; //Output pin injector 2 is on
pinInjector3 = PA3; //Output pin injector 3 is on
pinInjector4 = PA4; //Output pin injector 4 is on
pinInjector5 = PA5; //Output pin injector 5 is on
pinInjector6 = PD4; //Output pin injector 6 is on
pinCoil1 = PD7; //Pin for coil 1
pinCoil2 = PB9; //Pin for coil 2
pinCoil3 = PA8; //Pin for coil 3
pinCoil4 = PB10; //Pin for coil 4
pinCoil5 = PB11; //Pin for coil 5
pinMAP = PC0; //MAP sensor pin
pinTPS = PC1;//TPS input pin
pinIAT = PC2; //IAT sensor pin
pinCLT = PC3; //CLS sensor pin
pinO2 = PC5; //O2 Sensor pin
pinBat = PB1; //Battery reference voltage pin
pinBaro = PC4;
pinIdle1 = PB12; //Single wire idle control
pinIdle2 = PB11; //2 wire idle control
pinBoost = PC7; //Boost control
pinVVT_1 = PD3; //Default VVT output
pinStepperDir = PE0; //Direction pin for DRV8825 driver
pinStepperStep = PE1; //Step pin for DRV8825 driver
pinStepperEnable = PE2; //Enable pin for DRV8825
pinDisplayReset = PE5; // OLED reset pin
pinFan = PE6; //Pin for the fan output
pinFuelPump = PA6; //Fuel pump output
pinTachOut = PD15; //Tacho output pin
// pinLaunch = 51; //Can be overwritten below
// pinResetControl = 43; //Reset control output
//external interrupt enabled pins
//external interrupts could be enalbed in any pin, except same port numbers (PA4,PE4)
pinFlex = PD4; // Flex sensor (Must be external interrupt enabled)
pinTrigger = PD13; //The CAS pin
pinTrigger2 = PD14; //The Cam Sensor pin
break;
case 20:
//Pin mappings as per the v0.4 shield
//Black F407VE http://wiki.stm32duino.com/index.php?title=STM32F407
//PC8~PC12 SDio
//PA9..PA10 Serial1
//PA11..PA12 USB
//PA13..PA15 & PB4 SWD(debug) pins
//PB0 EEPROM CS pin
//PB1 LCD
//PB2 BOOT1
//PB3..PB5 SPI interface
//PB6..PB8 NRF interface
//PD5 & PD6 Serial2
pinInjector1 = PA1; //Output pin injector 1 is on
pinInjector2 = PA2; //Output pin injector 2 is on
pinInjector3 = PA3; //Output pin injector 3 is on
pinInjector4 = PA4; //Output pin injector 4 is on
pinInjector5 = PA5; //Output pin injector 5 is on
pinInjector6 = PD4; //Output pin injector 6 is on
pinCoil1 = PD7; //Pin for coil 1
pinCoil2 = PB9; //Pin for coil 2
pinCoil3 = PA8; //Pin for coil 3
pinCoil4 = PB10; //Pin for coil 4
pinCoil5 = PB11; //Pin for coil 5
pinMAP = PC0; //MAP sensor pin
pinTPS = PC1;//TPS input pin
pinIAT = PC2; //IAT sensor pin
pinCLT = PC3; //CLS sensor pin
pinO2 = PC5; //O2 Sensor pin
pinBat = PB1; //Battery reference voltage pin
pinBaro = PC4;
pinIdle1 = PB12; //Single wire idle control
pinIdle2 = PB11; //2 wire idle control
pinBoost = PC7; //Boost control
pinVVT_1 = PD3; //Default VVT output
pinStepperDir = PE0; //Direction pin for DRV8825 driver
pinStepperStep = PE1; //Step pin for DRV8825 driver
pinStepperEnable = PE2; //Enable pin for DRV8825
pinDisplayReset = PE5; // OLED reset pin
pinFan = PE6; //Pin for the fan output
pinFuelPump = PA6; //Fuel pump output
pinTachOut = PD15; //Tacho output pin
// pinLaunch = 51; //Can be overwritten below
// pinResetControl = 43; //Reset control output
//external interrupt enabled pins
//external interrupts could be enalbed in any pin, except same port numbers (PA4,PE4)
pinFlex = PD4; // Flex sensor (Must be external interrupt enabled)
pinTrigger = PD13; //The CAS pin
pinTrigger2 = PD14; //The Cam Sensor pin
break;
case 30:
//Pin mappings as per the v0.4 shield
//Black F407VE http://wiki.stm32duino.com/index.php?title=STM32F407
//PC8~PC12 SDio
//PA9..PA10 Serial1
//PA11..PA12 USB
//PA13..PA15 & PB4 SWD(debug) pins
//PB0 EEPROM CS pin
//PB1 LCD
//PB2 BOOT1
//PB3..PB5 SPI interface
//PB6..PB8 NRF interface
//PD5 & PD6 Serial2
pinInjector1 = PA1; //Output pin injector 1 is on
pinInjector2 = PA2; //Output pin injector 2 is on
pinInjector3 = PA3; //Output pin injector 3 is on
pinInjector4 = PA4; //Output pin injector 4 is on
pinInjector5 = PA5; //Output pin injector 5 is on
pinInjector6 = PD4; //Output pin injector 6 is on
pinCoil1 = PD7; //Pin for coil 1
pinCoil2 = PB9; //Pin for coil 2
pinCoil3 = PA8; //Pin for coil 3
pinCoil4 = PB10; //Pin for coil 4
pinCoil5 = PB11; //Pin for coil 5
pinMAP = PC0; //MAP sensor pin
pinTPS = PC1;//TPS input pin
pinIAT = PC2; //IAT sensor pin
pinCLT = PC3; //CLS sensor pin
pinO2 = PC5; //O2 Sensor pin
pinBat = PB1; //Battery reference voltage pin
pinBaro = PC4;
pinIdle1 = PB12; //Single wire idle control
pinIdle2 = PB11; //2 wire idle control
pinBoost = PC7; //Boost control
pinVVT_1 = PD3; //Default VVT output
pinStepperDir = PE0; //Direction pin for DRV8825 driver
pinStepperStep = PE1; //Step pin for DRV8825 driver
pinStepperEnable = PE2; //Enable pin for DRV8825
pinDisplayReset = PE5; // OLED reset pin
pinFan = PE6; //Pin for the fan output
pinFuelPump = PA6; //Fuel pump output
pinTachOut = PD15; //Tacho output pin
// pinLaunch = 51; //Can be overwritten below
// pinResetControl = 43; //Reset control output
//external interrupt enabled pins
//external interrupts could be enalbed in any pin, except same port numbers (PA4,PE4)
pinFlex = PD4; // Flex sensor (Must be external interrupt enabled)
pinTrigger = PD13; //The CAS pin
pinTrigger2 = PD14; //The Cam Sensor pin
break;
case 40:
//Pin mappings as per the v0.4 shield
//Black F407VE http://wiki.stm32duino.com/index.php?title=STM32F407
//PC8~PC12 SDio
//PA9..PA10 Serial1
//PA11..PA12 USB
//PA13..PA15 & PB4 SWD(debug) pins
//PB0 EEPROM CS pin
//PB1 LCD
//PB2 BOOT1
//PB3..PB5 SPI interface
//PB6..PB8 NRF interface
//PD5 & PD6 Serial2
pinInjector1 = PA1; //Output pin injector 1 is on
pinInjector2 = PA2; //Output pin injector 2 is on
pinInjector3 = PA3; //Output pin injector 3 is on
pinInjector4 = PA4; //Output pin injector 4 is on
pinInjector5 = PA5; //Output pin injector 5 is on
pinInjector6 = PD4; //Output pin injector 6 is on
pinCoil1 = PD7; //Pin for coil 1
pinCoil2 = PB9; //Pin for coil 2
pinCoil3 = PA8; //Pin for coil 3
pinCoil4 = PB10; //Pin for coil 4
pinCoil5 = PB11; //Pin for coil 5
pinMAP = PC0; //MAP sensor pin
pinTPS = PC1;//TPS input pin
pinIAT = PC2; //IAT sensor pin
pinCLT = PC3; //CLS sensor pin
pinO2 = PC5; //O2 Sensor pin
pinBat = PB1; //Battery reference voltage pin
pinBaro = PC4;
pinIdle1 = PB12; //Single wire idle control
pinIdle2 = PB11; //2 wire idle control
pinBoost = PC7; //Boost control
pinVVT_1 = PD3; //Default VVT output
pinStepperDir = PE0; //Direction pin for DRV8825 driver
pinStepperStep = PE1; //Step pin for DRV8825 driver
pinStepperEnable = PE2; //Enable pin for DRV8825
pinDisplayReset = PE5; // OLED reset pin
pinFan = PE6; //Pin for the fan output
pinFuelPump = PA6; //Fuel pump output
pinTachOut = PD15; //Tacho output pin
// pinLaunch = 51; //Can be overwritten below
// pinResetControl = 43; //Reset control output
//external interrupt enabled pins
//external interrupts could be enalbed in any pin, except same port numbers (PA4,PE4)
pinFlex = PD4; // Flex sensor (Must be external interrupt enabled)
pinTrigger = PD13; //The CAS pin
pinTrigger2 = PD14; //The Cam Sensor pin
case 41:
//Pin mappings as per the v0.4 shield
//Black F407VE http://wiki.stm32duino.com/index.php?title=STM32F407
//PC8~PC12 SDio
//PA9..PA10 Serial1
//PA11..PA12 USB
//PA13..PA15 & PB4 SWD(debug) pins
//PB0 EEPROM CS pin
//PB1 LCD
//PB2 BOOT1
//PB3..PB5 SPI interface
//PB6..PB8 NRF interface
//PD5 & PD6 Serial2
pinInjector1 = PA1; //Output pin injector 1 is on
pinInjector2 = PA2; //Output pin injector 2 is on
pinInjector3 = PA3; //Output pin injector 3 is on
pinInjector4 = PA4; //Output pin injector 4 is on
pinInjector5 = PA5; //Output pin injector 5 is on
pinInjector6 = PD4; //Output pin injector 6 is on
pinCoil1 = PD7; //Pin for coil 1
pinCoil2 = PB9; //Pin for coil 2
pinCoil3 = PA8; //Pin for coil 3
pinCoil4 = PB10; //Pin for coil 4
pinCoil5 = PB11; //Pin for coil 5
pinMAP = PC0; //MAP sensor pin
pinTPS = PC1;//TPS input pin
pinIAT = PC2; //IAT sensor pin
pinCLT = PC3; //CLS sensor pin
pinO2 = PC5; //O2 Sensor pin
pinBat = PB1; //Battery reference voltage pin
pinBaro = PC4;
pinIdle1 = PB12; //Single wire idle control
pinIdle2 = PB11; //2 wire idle control
pinBoost = PC7; //Boost control
pinVVT_1 = PD3; //Default VVT output
pinStepperDir = PE0; //Direction pin for DRV8825 driver
pinStepperStep = PE1; //Step pin for DRV8825 driver
pinStepperEnable = PE2; //Enable pin for DRV8825
pinDisplayReset = PE5; // OLED reset pin
pinFan = PE6; //Pin for the fan output
pinFuelPump = PA6; //Fuel pump output
pinTachOut = PD15; //Tacho output pin
// pinLaunch = 51; //Can be overwritten below
// pinResetControl = 43; //Reset control output
//external interrupt enabled pins
//external interrupts could be enalbed in any pin, except same port numbers (PA4,PE4)
pinFlex = PD4; // Flex sensor (Must be external interrupt enabled)
pinTrigger = PD13; //The CAS pin
pinTrigger2 = PD14; //The Cam Sensor pin
break;
default:
//Pin mappings as per the v0.4 shield
//Black F407VE http://wiki.stm32duino.com/index.php?title=STM32F407
//PC8~PC12 SDio
//PA9..PA10 Serial1
//PA11..PA12 USB
//PA13..PA15 & PB4 SWD(debug) pins
//PB0 EEPROM CS pin
//PB1 LCD
//PB2 BOOT1
//PB3..PB5 SPI interface
//PB6..PB8 NRF interface
//PD5 & PD6 Serial2
pinInjector1 = PA1; //Output pin injector 1 is on
pinInjector2 = PA2; //Output pin injector 2 is on
pinInjector3 = PA3; //Output pin injector 3 is on
pinInjector4 = PA4; //Output pin injector 4 is on
pinInjector5 = PA5; //Output pin injector 5 is on
pinInjector6 = PD4; //Output pin injector 6 is on
pinCoil1 = PD7; //Pin for coil 1
pinCoil2 = PB9; //Pin for coil 2
pinCoil3 = PA8; //Pin for coil 3
pinCoil4 = PB10; //Pin for coil 4
pinCoil5 = PB11; //Pin for coil 5
pinMAP = PC0; //MAP sensor pin
pinTPS = PC1;//TPS input pin
pinIAT = PC2; //IAT sensor pin
pinCLT = PC3; //CLS sensor pin
pinO2 = PC5; //O2 Sensor pin
pinBat = PB1; //Battery reference voltage pin
pinBaro = PC4;
pinIdle1 = PB12; //Single wire idle control
pinIdle2 = PB11; //2 wire idle control
pinBoost = PC7; //Boost control
pinVVT_1 = PD3; //Default VVT output
pinStepperDir = PE0; //Direction pin for DRV8825 driver
pinStepperStep = PE1; //Step pin for DRV8825 driver
pinStepperEnable = PE2; //Enable pin for DRV8825
pinDisplayReset = PE5; // OLED reset pin
pinFan = PE6; //Pin for the fan output
pinFuelPump = PA6; //Fuel pump output
pinTachOut = PD15; //Tacho output pin
// pinLaunch = 51; //Can be overwritten below
// pinResetControl = 43; //Reset control output
//external interrupt enabled pins
//external interrupts could be enalbed in any pin, except same port numbers (PA4,PE4)
pinFlex = PD4; // Flex sensor (Must be external interrupt enabled)
pinTrigger = PD13; //The CAS pin
pinTrigger2 = PD14; //The Cam Sensor pin
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
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);
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);
//Set default values
digitalWrite(pinMAP, HIGH);
//digitalWrite(pinO2, LOW);
digitalWrite(pinTPS, LOW);
}
#endif #endif

View File

@ -0,0 +1,151 @@
#ifndef STM32F407VE_H
#define STM32F407VE_H
#if defined(ARDUINO_BLACK_F407VE)
/*
***********************************************************************************************************
* General
*/
#define PORT_TYPE uint32_t
#define PINMAKS_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()
#define USE_SERIAL3
void initBoard();
uint16_t freeRam();
// extern void oneMSIntervalIRQ(stimer_t *Timer);
extern void EmptyIRQCallback(stimer_t *Timer, uint32_t channel);
/*
***********************************************************************************************************
* Schedules
*/
#define MAX_TIMER_PERIOD 65535*4 //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*4//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>>2) //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>>2) //Converts a given number of uS into the required number of timer ticks until that time has passed.
#define FUEL1_COUNTER (TIM3)->CNT
#define FUEL2_COUNTER (TIM3)->CNT
#define FUEL3_COUNTER (TIM3)->CNT
#define FUEL4_COUNTER (TIM3)->CNT
#define FUEL1_COMPARE (TIM3)->CCR1
#define FUEL2_COMPARE (TIM3)->CCR2
#define FUEL3_COMPARE (TIM3)->CCR3
#define FUEL4_COMPARE (TIM3)->CCR4
#define IGN1_COUNTER (TIM2)->CNT
#define IGN2_COUNTER (TIM2)->CNT
#define IGN3_COUNTER (TIM2)->CNT
#define IGN4_COUNTER (TIM2)->CNT
#define IGN1_COMPARE (TIM2)->CCR1
#define IGN2_COMPARE (TIM2)->CCR2
#define IGN3_COMPARE (TIM2)->CCR3
#define IGN4_COMPARE (TIM2)->CCR4
#define FUEL5_COUNTER (TIM5)->CNT
#define FUEL6_COUNTER (TIM5)->CNT
#define FUEL7_COUNTER (TIM5)->CNT
#define FUEL8_COUNTER (TIM5)->CNT
#define FUEL5_COMPARE (TIM5)->CCR1
#define FUEL6_COMPARE (TIM5)->CCR2
#define FUEL7_COMPARE (TIM5)->CCR3
#define FUEL8_COMPARE (TIM5)->CCR4
#define IGN5_COUNTER (TIM4)->CNT
#define IGN6_COUNTER (TIM4)->CNT
#define IGN7_COUNTER (TIM4)->CNT
#define IGN8_COUNTER (TIM4)->CNT
#define IGN5_COMPARE (TIM4)->CCR1
#define IGN6_COMPARE (TIM4)->CCR2
#define IGN7_COMPARE (TIM4)->CCR3
#define IGN8_COMPARE (TIM4)->CCR4
#define FUEL1_TIMER_ENABLE() (TIM3)->CCER |= TIM_CCER_CC1E
#define FUEL2_TIMER_ENABLE() (TIM3)->CCER |= TIM_CCER_CC2E
#define FUEL3_TIMER_ENABLE() (TIM3)->CCER |= TIM_CCER_CC3E
#define FUEL4_TIMER_ENABLE() (TIM3)->CCER |= TIM_CCER_CC4E
#define FUEL1_TIMER_DISABLE() (TIM3)->CCER &= ~TIM_CCER_CC1E
#define FUEL2_TIMER_DISABLE() (TIM3)->CCER &= ~TIM_CCER_CC2E
#define FUEL3_TIMER_DISABLE() (TIM3)->CCER &= ~TIM_CCER_CC3E
#define FUEL4_TIMER_DISABLE() (TIM3)->CCER &= ~TIM_CCER_CC4E
#define IGN1_TIMER_ENABLE() (TIM2)->CCER |= TIM_CCER_CC1E
#define IGN2_TIMER_ENABLE() (TIM2)->CCER |= TIM_CCER_CC2E
#define IGN3_TIMER_ENABLE() (TIM2)->CCER |= TIM_CCER_CC3E
#define IGN4_TIMER_ENABLE() (TIM2)->CCER |= TIM_CCER_CC4E
#define IGN1_TIMER_DISABLE() (TIM2)->CCER &= ~TIM_CCER_CC1E
#define IGN2_TIMER_DISABLE() (TIM2)->CCER &= ~TIM_CCER_CC2E
#define IGN3_TIMER_DISABLE() (TIM2)->CCER &= ~TIM_CCER_CC3E
#define IGN4_TIMER_DISABLE() (TIM2)->CCER &= ~TIM_CCER_CC4E
#define FUEL5_TIMER_ENABLE() (TIM5)->CCER |= TIM_CCER_CC1E
#define FUEL6_TIMER_ENABLE() (TIM5)->CCER |= TIM_CCER_CC2E
#define FUEL7_TIMER_ENABLE() (TIM5)->CCER |= TIM_CCER_CC3E
#define FUEL8_TIMER_ENABLE() (TIM5)->CCER |= TIM_CCER_CC4E
#define FUEL5_TIMER_DISABLE() (TIM5)->CCER &= ~TIM_CCER_CC1E
#define FUEL6_TIMER_DISABLE() (TIM5)->CCER &= ~TIM_CCER_CC2E
#define FUEL7_TIMER_DISABLE() (TIM5)->CCER &= ~TIM_CCER_CC3E
#define FUEL8_TIMER_DISABLE() (TIM5)->CCER &= ~TIM_CCER_CC4E
#define IGN5_TIMER_ENABLE() (TIM4)->CCER |= TIM_CCER_CC1E
#define IGN6_TIMER_ENABLE() (TIM4)->CCER |= TIM_CCER_CC2E
#define IGN7_TIMER_ENABLE() (TIM4)->CCER |= TIM_CCER_CC3E
#define IGN8_TIMER_ENABLE() (TIM4)->CCER |= TIM_CCER_CC4E
#define IGN5_TIMER_DISABLE() (TIM4)->CCER &= ~TIM_CCER_CC1E
#define IGN6_TIMER_DISABLE() (TIM4)->CCER &= ~TIM_CCER_CC2E
#define IGN7_TIMER_DISABLE() (TIM4)->CCER &= ~TIM_CCER_CC3E
#define IGN8_TIMER_DISABLE() (TIM4)->CCER &= ~TIM_CCER_CC4E
/*
***********************************************************************************************************
* Auxilliaries
*/
#define ENABLE_BOOST_TIMER() (TIM1)->CCER |= TIM_CCER_CC2E
#define DISABLE_BOOST_TIMER() (TIM1)->CCER &= ~TIM_CCER_CC2E
#define ENABLE_VVT_TIMER() (TIM1)->CCER |= TIM_CCER_CC3E
#define DISABLE_VVT_TIMER() (TIM1)->CCER &= ~TIM_CCER_CC3E
#define BOOST_TIMER_COMPARE (TIM1)->CCR2
#define BOOST_TIMER_COUNTER (TIM1)->CNT
#define VVT_TIMER_COMPARE (TIM1)->CCR3
#define VVT_TIMER_COUNTER (TIM1)->CNT
/*
***********************************************************************************************************
* Idle
*/
#define IDLE_COUNTER (TIM1)->CNT
#define IDLE_COMPARE (TIM1)->CCR4
#define IDLE_TIMER_ENABLE() (TIM1)->CCER |= TIM_CCER_CC4E
#define IDLE_TIMER_DISABLE() (TIM1)->CCER &= ~TIM_CCER_CC4E
/*
***********************************************************************************************************
* Timers
*/
/*
***********************************************************************************************************
* CAN / Second serial
*/
HardwareSerial CANSerial(PD6,PD5);
#endif //CORE_STM32
#endif //STM32_H

View File

@ -0,0 +1,901 @@
#if defined(ARDUINO_BLACK_F407VE)
#include "board_stm32F407VE.h"
#include "globals.h"
#include "auxiliaries.h"
#include "idle.h"
#include "scheduler.h"
#if defined(STM32F4)
#define NR_OFF_TIMERS 9
//stimer_t HardwareTimers[NR_OFF_TIMERS + 1];
stimer_t HardwareTimers_1;
stimer_t HardwareTimers_2;
stimer_t HardwareTimers_3;
stimer_t HardwareTimers_4;
stimer_t HardwareTimers_5;
stimer_t HardwareTimers_8;
#define LED_BUILTIN PA7
//These should really be in the stm32GENERIC libs, but for somereason they only have timers 1-4
// #include <stm32_TIM_variant_11.h>
// #include "src/HardwareTimers/HardwareTimer.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]));
#else
#include "HardwareTimer.h"
#endif
extern void oneMSIntervalIRQ(stimer_t *Timer){oneMSInterval();}
extern void EmptyIRQCallback(stimer_t *Timer, uint32_t channel){}
void initBoard()
{
/*
* Initialize timers
*/
HardwareTimers_1.timer = TIM1;
HardwareTimers_2.timer = TIM2;
HardwareTimers_3.timer = TIM3;
HardwareTimers_4.timer = TIM4;
HardwareTimers_5.timer = TIM5;
HardwareTimers_8.timer = TIM8;
/*
***********************************************************************************************************
* General
*/
#define FLASH_LENGTH 8192
/*
***********************************************************************************************************
* Idle
*/
if( (configPage6.iacAlgorithm == IAC_ALGORITHM_PWM_OL) || (configPage6.iacAlgorithm == IAC_ALGORITHM_PWM_CL) )
{
idle_pwm_max_count = 1000000L / (configPage6.idleFreq * 2); //Converts the frequency in Hz to the number of ticks (at 2uS) it takes to complete 1 cycle. Note that the frequency is divided by 2 coming from TS to allow for up to 5KHz
}
//This must happen at the end of the idle init
TimerPulseInit(&HardwareTimers_1, 0xFFFF, 0, EmptyIRQCallback);
//setTimerPrescalerRegister(&HardwareTimers_1, (uint32_t)(getTimerClkFreq(HardwareTimers_1.timer) / (500000)) - 1);
if(idle_pwm_max_count > 0) { attachIntHandleOC(&HardwareTimers_1, idleInterrupt, 4, 0);} //on first flash the configPage4.iacAlgorithm is invalid
//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();
/*
***********************************************************************************************************
* Timers
*/
#if defined(ARDUINO_BLACK_F407VE) || defined(STM32F4) || defined(_STM32F4_)
TimerHandleInit(&HardwareTimers_8, 1000, 168);
attachIntHandle(&HardwareTimers_8, oneMSIntervalIRQ);
#else
Timer4.setPeriod(1000); // Set up period
Timer4.setMode(1, TIMER_OUTPUT_COMPARE);
Timer4.attachInterrupt(1, oneMSInterval);
Timer4.resume(); //Start Timer
#endif
pinMode(LED_BUILTIN, OUTPUT); //Visual WDT
/*
***********************************************************************************************************
* Auxilliaries
*/
//2uS resolution Min 8Hz, Max 5KHz
boost_pwm_max_count = 1000000L / (2 * configPage6.boostFreq * 2); //Converts the frequency in Hz to the number of ticks (at 2uS) it takes to complete 1 cycle. The x2 is there because the frequency is stored at half value (in a byte) to allow freqneucies up to 511Hz
vvt_pwm_max_count = 1000000L / (2 * configPage6.vvtFreq * 2); //Converts the frequency in Hz to the number of ticks (at 2uS) it takes to complete 1 cycle
//Need to be initialised last due to instant interrupt
// Timer1.setMode(2, TIMER_OUTPUT_COMPARE);
// 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);}
if(idle_pwm_max_count > 0) { attachIntHandleOC(&HardwareTimers_1, boostInterrupt, 2, 0);}
if(vvt_pwm_max_count > 0) { attachIntHandleOC(&HardwareTimers_1, vvtInterrupt, 3, 0);}
// Timer1.resume();
TimerPulseInit(&HardwareTimers_3, 0xFFFF, 0, EmptyIRQCallback);
attachIntHandleOC(&HardwareTimers_3, fuelSchedule1Interrupt, 1, 0);
attachIntHandleOC(&HardwareTimers_3, fuelSchedule2Interrupt, 2, 0);
attachIntHandleOC(&HardwareTimers_3, fuelSchedule3Interrupt, 3, 0);
attachIntHandleOC(&HardwareTimers_3, fuelSchedule4Interrupt, 4, 0);
TimerPulseInit(&HardwareTimers_2, 0xFFFF, 0, EmptyIRQCallback);
attachIntHandleOC(&HardwareTimers_2, ignitionSchedule1Interrupt, 1, 0);
attachIntHandleOC(&HardwareTimers_2, ignitionSchedule2Interrupt, 2, 0);
attachIntHandleOC(&HardwareTimers_2, ignitionSchedule3Interrupt, 3, 0);
attachIntHandleOC(&HardwareTimers_2, ignitionSchedule4Interrupt, 4, 0);
//Attach interupt functions
//Injection
TimerPulseInit(&HardwareTimers_5, 0xFFFF, 0, EmptyIRQCallback);
//setTimerPrescalerRegister(&HardwareTimers_5, (uint32_t)(getTimerClkFreq(HardwareTimers_5.timer) / (1000000)) - 1);
#if (INJ_CHANNELS >= 5)
attachIntHandleOC(&HardwareTimers_5, fuelSchedule5Interrupt, 1, 0);
//Timer5.attachInterrupt(1, fuelSchedule5Interrupt);
#endif
#if (INJ_CHANNELS >= 6)
attachIntHandleOC(&HardwareTimers_5, fuelSchedule6Interrupt, 2, 0);
//Timer5.attachInterrupt(2, fuelSchedule6Interrupt);
#endif
#if (INJ_CHANNELS >= 7)
attachIntHandleOC(&HardwareTimers_5, fuelSchedule7Interrupt, 3, 0);
//Timer5.attachInterrupt(3, fuelSchedule7Interrupt);
#endif
#if (INJ_CHANNELS >= 8)
attachIntHandleOC(&HardwareTimers_5, fuelSchedule8Interrupt, 4, 0);
//Timer5.attachInterrupt(4, fuelSchedule8Interrupt);
#endif
TimerPulseInit(&HardwareTimers_4, 0xFFFF, 0, EmptyIRQCallback);
//setTimerPrescalerRegister(&HardwareTimers_4, (uint32_t)(getTimerClkFreq(HardwareTimers_4.timer) / (1000000)) - 1);
#if (IGN_CHANNELS >= 5)
attachIntHandleOC(&HardwareTimers_4, ignitionSchedule5Interrupt, 1, 0);
//Timer4.attachInterrupt(1, ignitionSchedule5Interrupt);
#endif
#if (IGN_CHANNELS >= 6)
attachIntHandleOC(&HardwareTimers_4, ignitionSchedule6Interrupt, 2, 0);
//Timer4.attachInterrupt(2, ignitionSchedule6Interrupt);
#endif
#if (IGN_CHANNELS >= 7)
attachIntHandleOC(&HardwareTimers_4, ignitionSchedule7Interrupt, 3, 0);
//Timer4.attachInterrupt(3, ignitionSchedule7Interrupt);
#endif
#if (IGN_CHANNELS >= 8)
attachIntHandleOC(&HardwareTimers_4, ignitionSchedule8Interrupt, 4, 0);
//Timer4.attachInterrupt(4, ignitionSchedule8Interrupt);
#endif
setTimerPrescalerRegister(&HardwareTimers_2, (uint32_t)(getTimerClkFreq(HardwareTimers_2.timer) / (250000)) - 1);
setTimerPrescalerRegister(&HardwareTimers_3, (uint32_t)(getTimerClkFreq(HardwareTimers_3.timer) / (250000)) - 1);
setTimerPrescalerRegister(&HardwareTimers_4, (uint32_t)(getTimerClkFreq(HardwareTimers_4.timer) / (250000)) - 1);
setTimerPrescalerRegister(&HardwareTimers_5, (uint32_t)(getTimerClkFreq(HardwareTimers_5.timer) / (250000)) - 1);
}
uint16_t freeRam()
{
char top = 't';
return &top - reinterpret_cast<char*>(sbrk(0));
}
//pinmapping the STM32F407 for different boards, at this moment no board is desgined.
//All boards are set to the default just to be sure.
void setPinMapping(byte boardID)
{
switch (boardID)
{
case 0:
//Pin mappings as per the v0.4 shield
//Black F407VE http://wiki.stm32duino.com/index.php?title=STM32F407
//PC8~PC12 SDio
//PA9..PA10 Serial1
//PA11..PA12 USB
//PA13..PA15 & PB4 SWD(debug) pins
//PB0 EEPROM CS pin
//PB1 LCD
//PB2 BOOT1
//PB3..PB5 SPI interface
//PB6..PB8 NRF interface
//PD5 & PD6 Serial2
pinInjector1 = PA1; //Output pin injector 1 is on
pinInjector2 = PA2; //Output pin injector 2 is on
pinInjector3 = PA3; //Output pin injector 3 is on
pinInjector4 = PA4; //Output pin injector 4 is on
pinInjector5 = PA5; //Output pin injector 5 is on
pinInjector6 = PD4; //Output pin injector 6 is on
pinCoil1 = PD7; //Pin for coil 1
pinCoil2 = PB9; //Pin for coil 2
pinCoil3 = PA8; //Pin for coil 3
pinCoil4 = PB10; //Pin for coil 4
pinCoil5 = PB11; //Pin for coil 5
pinMAP = PC0; //MAP sensor pin
pinTPS = PC1;//TPS input pin
pinIAT = PC2; //IAT sensor pin
pinCLT = PC3; //CLS sensor pin
pinO2 = PC5; //O2 Sensor pin
pinBat = PB1; //Battery reference voltage pin
pinBaro = PC4;
pinIdle1 = PB12; //Single wire idle control
pinIdle2 = PB11; //2 wire idle control
pinBoost = PC7; //Boost control
pinVVT_1 = PD3; //Default VVT output
pinStepperDir = PE0; //Direction pin for DRV8825 driver
pinStepperStep = PE1; //Step pin for DRV8825 driver
pinStepperEnable = PE2; //Enable pin for DRV8825
pinDisplayReset = PE5; // OLED reset pin
pinFan = PE6; //Pin for the fan output
pinFuelPump = PA6; //Fuel pump output
pinTachOut = PD15; //Tacho output pin
// pinLaunch = 51; //Can be overwritten below
// pinResetControl = 43; //Reset control output
//external interrupt enabled pins
//external interrupts could be enalbed in any pin, except same port numbers (PA4,PE4)
pinFlex = PD4; // Flex sensor (Must be external interrupt enabled)
pinTrigger = PD13; //The CAS pin
pinTrigger2 = PD14; //The Cam Sensor pin
break;
case 1:
//Pin mappings as per the v0.4 shield
//Black F407VE http://wiki.stm32duino.com/index.php?title=STM32F407
//PC8~PC12 SDio
//PA9..PA10 Serial1
//PA11..PA12 USB
//PA13..PA15 & PB4 SWD(debug) pins
//PB0 EEPROM CS pin
//PB1 LCD
//PB2 BOOT1
//PB3..PB5 SPI interface
//PB6..PB8 NRF interface
//PD5 & PD6 Serial2
pinInjector1 = PA1; //Output pin injector 1 is on
pinInjector2 = PA2; //Output pin injector 2 is on
pinInjector3 = PA3; //Output pin injector 3 is on
pinInjector4 = PA4; //Output pin injector 4 is on
pinInjector5 = PA5; //Output pin injector 5 is on
pinInjector6 = PD4; //Output pin injector 6 is on
pinCoil1 = PD7; //Pin for coil 1
pinCoil2 = PB9; //Pin for coil 2
pinCoil3 = PA8; //Pin for coil 3
pinCoil4 = PB10; //Pin for coil 4
pinCoil5 = PB11; //Pin for coil 5
pinMAP = PC0; //MAP sensor pin
pinTPS = PC1;//TPS input pin
pinIAT = PC2; //IAT sensor pin
pinCLT = PC3; //CLS sensor pin
pinO2 = PC5; //O2 Sensor pin
pinBat = PB1; //Battery reference voltage pin
pinBaro = PC4;
pinIdle1 = PB12; //Single wire idle control
pinIdle2 = PB11; //2 wire idle control
pinBoost = PC7; //Boost control
pinVVT_1 = PD3; //Default VVT output
pinStepperDir = PE0; //Direction pin for DRV8825 driver
pinStepperStep = PE1; //Step pin for DRV8825 driver
pinStepperEnable = PE2; //Enable pin for DRV8825
pinDisplayReset = PE5; // OLED reset pin
pinFan = PE6; //Pin for the fan output
pinFuelPump = PA6; //Fuel pump output
pinTachOut = PD15; //Tacho output pin
// pinLaunch = 51; //Can be overwritten below
// pinResetControl = 43; //Reset control output
//external interrupt enabled pins
//external interrupts could be enalbed in any pin, except same port numbers (PA4,PE4)
pinFlex = PD4; // Flex sensor (Must be external interrupt enabled)
pinTrigger = PD13; //The CAS pin
pinTrigger2 = PD14; //The Cam Sensor pin
break;
case 2:
//Pin mappings as per the v0.4 shield
//Black F407VE http://wiki.stm32duino.com/index.php?title=STM32F407
//PC8~PC12 SDio
//PA9..PA10 Serial1
//PA11..PA12 USB
//PA13..PA15 & PB4 SWD(debug) pins
//PB0 EEPROM CS pin
//PB1 LCD
//PB2 BOOT1
//PB3..PB5 SPI interface
//PB6..PB8 NRF interface
//PD5 & PD6 Serial2
pinInjector1 = PA1; //Output pin injector 1 is on
pinInjector2 = PA2; //Output pin injector 2 is on
pinInjector3 = PA3; //Output pin injector 3 is on
pinInjector4 = PA4; //Output pin injector 4 is on
pinInjector5 = PA5; //Output pin injector 5 is on
pinInjector6 = PD4; //Output pin injector 6 is on
pinCoil1 = PD7; //Pin for coil 1
pinCoil2 = PB9; //Pin for coil 2
pinCoil3 = PA8; //Pin for coil 3
pinCoil4 = PB10; //Pin for coil 4
pinCoil5 = PB11; //Pin for coil 5
pinMAP = PC0; //MAP sensor pin
pinTPS = PC1;//TPS input pin
pinIAT = PC2; //IAT sensor pin
pinCLT = PC3; //CLS sensor pin
pinO2 = PC5; //O2 Sensor pin
pinBat = PB1; //Battery reference voltage pin
pinBaro = PC4;
pinIdle1 = PB12; //Single wire idle control
pinIdle2 = PB11; //2 wire idle control
pinBoost = PC7; //Boost control
pinVVT_1 = PD3; //Default VVT output
pinStepperDir = PE0; //Direction pin for DRV8825 driver
pinStepperStep = PE1; //Step pin for DRV8825 driver
pinStepperEnable = PE2; //Enable pin for DRV8825
pinDisplayReset = PE5; // OLED reset pin
pinFan = PE6; //Pin for the fan output
pinFuelPump = PA6; //Fuel pump output
pinTachOut = PD15; //Tacho output pin
// pinLaunch = 51; //Can be overwritten below
// pinResetControl = 43; //Reset control output
//external interrupt enabled pins
//external interrupts could be enalbed in any pin, except same port numbers (PA4,PE4)
pinFlex = PD4; // Flex sensor (Must be external interrupt enabled)
pinTrigger = PD13; //The CAS pin
pinTrigger2 = PD14; //The Cam Sensor pin
break;
case 3:
//Pin mappings as per the v0.4 shield
//Black F407VE http://wiki.stm32duino.com/index.php?title=STM32F407
//PC8~PC12 SDio
//PA9..PA10 Serial1
//PA11..PA12 USB
//PA13..PA15 & PB4 SWD(debug) pins
//PB0 EEPROM CS pin
//PB1 LCD
//PB2 BOOT1
//PB3..PB5 SPI interface
//PB6..PB8 NRF interface
//PD5 & PD6 Serial2
pinInjector1 = PA1; //Output pin injector 1 is on
pinInjector2 = PA2; //Output pin injector 2 is on
pinInjector3 = PA3; //Output pin injector 3 is on
pinInjector4 = PA4; //Output pin injector 4 is on
pinInjector5 = PA5; //Output pin injector 5 is on
pinInjector6 = PD4; //Output pin injector 6 is on
pinCoil1 = PD7; //Pin for coil 1
pinCoil2 = PB9; //Pin for coil 2
pinCoil3 = PA8; //Pin for coil 3
pinCoil4 = PB10; //Pin for coil 4
pinCoil5 = PB11; //Pin for coil 5
pinMAP = PC0; //MAP sensor pin
pinTPS = PC1;//TPS input pin
pinIAT = PC2; //IAT sensor pin
pinCLT = PC3; //CLS sensor pin
pinO2 = PC5; //O2 Sensor pin
pinBat = PB1; //Battery reference voltage pin
pinBaro = PC4;
pinIdle1 = PB12; //Single wire idle control
pinIdle2 = PB11; //2 wire idle control
pinBoost = PC7; //Boost control
pinVVT_1 = PD3; //Default VVT output
pinStepperDir = PE0; //Direction pin for DRV8825 driver
pinStepperStep = PE1; //Step pin for DRV8825 driver
pinStepperEnable = PE2; //Enable pin for DRV8825
pinDisplayReset = PE5; // OLED reset pin
pinFan = PE6; //Pin for the fan output
pinFuelPump = PA6; //Fuel pump output
pinTachOut = PD15; //Tacho output pin
// pinLaunch = 51; //Can be overwritten below
// pinResetControl = 43; //Reset control output
//external interrupt enabled pins
//external interrupts could be enalbed in any pin, except same port numbers (PA4,PE4)
pinFlex = PD4; // Flex sensor (Must be external interrupt enabled)
pinTrigger = PD13; //The CAS pin
pinTrigger2 = PD14; //The Cam Sensor pin
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
break;
case 10:
//Pin mappings as per the v0.4 shield
//Black F407VE http://wiki.stm32duino.com/index.php?title=STM32F407
//PC8~PC12 SDio
//PA9..PA10 Serial1
//PA11..PA12 USB
//PA13..PA15 & PB4 SWD(debug) pins
//PB0 EEPROM CS pin
//PB1 LCD
//PB2 BOOT1
//PB3..PB5 SPI interface
//PB6..PB8 NRF interface
//PD5 & PD6 Serial2
pinInjector1 = PA1; //Output pin injector 1 is on
pinInjector2 = PA2; //Output pin injector 2 is on
pinInjector3 = PA3; //Output pin injector 3 is on
pinInjector4 = PA4; //Output pin injector 4 is on
pinInjector5 = PA5; //Output pin injector 5 is on
pinInjector6 = PD4; //Output pin injector 6 is on
pinCoil1 = PD7; //Pin for coil 1
pinCoil2 = PB9; //Pin for coil 2
pinCoil3 = PA8; //Pin for coil 3
pinCoil4 = PB10; //Pin for coil 4
pinCoil5 = PB11; //Pin for coil 5
pinMAP = PC0; //MAP sensor pin
pinTPS = PC1;//TPS input pin
pinIAT = PC2; //IAT sensor pin
pinCLT = PC3; //CLS sensor pin
pinO2 = PC5; //O2 Sensor pin
pinBat = PB1; //Battery reference voltage pin
pinBaro = PC4;
pinIdle1 = PB12; //Single wire idle control
pinIdle2 = PB11; //2 wire idle control
pinBoost = PC7; //Boost control
pinVVT_1 = PD3; //Default VVT output
pinStepperDir = PE0; //Direction pin for DRV8825 driver
pinStepperStep = PE1; //Step pin for DRV8825 driver
pinStepperEnable = PE2; //Enable pin for DRV8825
pinDisplayReset = PE5; // OLED reset pin
pinFan = PE6; //Pin for the fan output
pinFuelPump = PA6; //Fuel pump output
pinTachOut = PD15; //Tacho output pin
// pinLaunch = 51; //Can be overwritten below
// pinResetControl = 43; //Reset control output
//external interrupt enabled pins
//external interrupts could be enalbed in any pin, except same port numbers (PA4,PE4)
pinFlex = PD4; // Flex sensor (Must be external interrupt enabled)
pinTrigger = PD13; //The CAS pin
pinTrigger2 = PD14; //The Cam Sensor pin
break;
case 20:
//Pin mappings as per the v0.4 shield
//Black F407VE http://wiki.stm32duino.com/index.php?title=STM32F407
//PC8~PC12 SDio
//PA9..PA10 Serial1
//PA11..PA12 USB
//PA13..PA15 & PB4 SWD(debug) pins
//PB0 EEPROM CS pin
//PB1 LCD
//PB2 BOOT1
//PB3..PB5 SPI interface
//PB6..PB8 NRF interface
//PD5 & PD6 Serial2
pinInjector1 = PA1; //Output pin injector 1 is on
pinInjector2 = PA2; //Output pin injector 2 is on
pinInjector3 = PA3; //Output pin injector 3 is on
pinInjector4 = PA4; //Output pin injector 4 is on
pinInjector5 = PA5; //Output pin injector 5 is on
pinInjector6 = PD4; //Output pin injector 6 is on
pinCoil1 = PD7; //Pin for coil 1
pinCoil2 = PB9; //Pin for coil 2
pinCoil3 = PA8; //Pin for coil 3
pinCoil4 = PB10; //Pin for coil 4
pinCoil5 = PB11; //Pin for coil 5
pinMAP = PC0; //MAP sensor pin
pinTPS = PC1;//TPS input pin
pinIAT = PC2; //IAT sensor pin
pinCLT = PC3; //CLS sensor pin
pinO2 = PC5; //O2 Sensor pin
pinBat = PB1; //Battery reference voltage pin
pinBaro = PC4;
pinIdle1 = PB12; //Single wire idle control
pinIdle2 = PB11; //2 wire idle control
pinBoost = PC7; //Boost control
pinVVT_1 = PD3; //Default VVT output
pinStepperDir = PE0; //Direction pin for DRV8825 driver
pinStepperStep = PE1; //Step pin for DRV8825 driver
pinStepperEnable = PE2; //Enable pin for DRV8825
pinDisplayReset = PE5; // OLED reset pin
pinFan = PE6; //Pin for the fan output
pinFuelPump = PA6; //Fuel pump output
pinTachOut = PD15; //Tacho output pin
// pinLaunch = 51; //Can be overwritten below
// pinResetControl = 43; //Reset control output
//external interrupt enabled pins
//external interrupts could be enalbed in any pin, except same port numbers (PA4,PE4)
pinFlex = PD4; // Flex sensor (Must be external interrupt enabled)
pinTrigger = PD13; //The CAS pin
pinTrigger2 = PD14; //The Cam Sensor pin
break;
case 30:
//Pin mappings as per the v0.4 shield
//Black F407VE http://wiki.stm32duino.com/index.php?title=STM32F407
//PC8~PC12 SDio
//PA9..PA10 Serial1
//PA11..PA12 USB
//PA13..PA15 & PB4 SWD(debug) pins
//PB0 EEPROM CS pin
//PB1 LCD
//PB2 BOOT1
//PB3..PB5 SPI interface
//PB6..PB8 NRF interface
//PD5 & PD6 Serial2
pinInjector1 = PA1; //Output pin injector 1 is on
pinInjector2 = PA2; //Output pin injector 2 is on
pinInjector3 = PA3; //Output pin injector 3 is on
pinInjector4 = PA4; //Output pin injector 4 is on
pinInjector5 = PA5; //Output pin injector 5 is on
pinInjector6 = PD4; //Output pin injector 6 is on
pinCoil1 = PD7; //Pin for coil 1
pinCoil2 = PB9; //Pin for coil 2
pinCoil3 = PA8; //Pin for coil 3
pinCoil4 = PB10; //Pin for coil 4
pinCoil5 = PB11; //Pin for coil 5
pinMAP = PC0; //MAP sensor pin
pinTPS = PC1;//TPS input pin
pinIAT = PC2; //IAT sensor pin
pinCLT = PC3; //CLS sensor pin
pinO2 = PC5; //O2 Sensor pin
pinBat = PB1; //Battery reference voltage pin
pinBaro = PC4;
pinIdle1 = PB12; //Single wire idle control
pinIdle2 = PB11; //2 wire idle control
pinBoost = PC7; //Boost control
pinVVT_1 = PD3; //Default VVT output
pinStepperDir = PE0; //Direction pin for DRV8825 driver
pinStepperStep = PE1; //Step pin for DRV8825 driver
pinStepperEnable = PE2; //Enable pin for DRV8825
pinDisplayReset = PE5; // OLED reset pin
pinFan = PE6; //Pin for the fan output
pinFuelPump = PA6; //Fuel pump output
pinTachOut = PD15; //Tacho output pin
// pinLaunch = 51; //Can be overwritten below
// pinResetControl = 43; //Reset control output
//external interrupt enabled pins
//external interrupts could be enalbed in any pin, except same port numbers (PA4,PE4)
pinFlex = PD4; // Flex sensor (Must be external interrupt enabled)
pinTrigger = PD13; //The CAS pin
pinTrigger2 = PD14; //The Cam Sensor pin
break;
case 40:
//Pin mappings as per the v0.4 shield
//Black F407VE http://wiki.stm32duino.com/index.php?title=STM32F407
//PC8~PC12 SDio
//PA9..PA10 Serial1
//PA11..PA12 USB
//PA13..PA15 & PB4 SWD(debug) pins
//PB0 EEPROM CS pin
//PB1 LCD
//PB2 BOOT1
//PB3..PB5 SPI interface
//PB6..PB8 NRF interface
//PD5 & PD6 Serial2
pinInjector1 = PA1; //Output pin injector 1 is on
pinInjector2 = PA2; //Output pin injector 2 is on
pinInjector3 = PA3; //Output pin injector 3 is on
pinInjector4 = PA4; //Output pin injector 4 is on
pinInjector5 = PA5; //Output pin injector 5 is on
pinInjector6 = PD4; //Output pin injector 6 is on
pinCoil1 = PD7; //Pin for coil 1
pinCoil2 = PB9; //Pin for coil 2
pinCoil3 = PA8; //Pin for coil 3
pinCoil4 = PB10; //Pin for coil 4
pinCoil5 = PB11; //Pin for coil 5
pinMAP = PC0; //MAP sensor pin
pinTPS = PC1;//TPS input pin
pinIAT = PC2; //IAT sensor pin
pinCLT = PC3; //CLS sensor pin
pinO2 = PC5; //O2 Sensor pin
pinBat = PB1; //Battery reference voltage pin
pinBaro = PC4;
pinIdle1 = PB12; //Single wire idle control
pinIdle2 = PB11; //2 wire idle control
pinBoost = PC7; //Boost control
pinVVT_1 = PD3; //Default VVT output
pinStepperDir = PE0; //Direction pin for DRV8825 driver
pinStepperStep = PE1; //Step pin for DRV8825 driver
pinStepperEnable = PE2; //Enable pin for DRV8825
pinDisplayReset = PE5; // OLED reset pin
pinFan = PE6; //Pin for the fan output
pinFuelPump = PA6; //Fuel pump output
pinTachOut = PD15; //Tacho output pin
// pinLaunch = 51; //Can be overwritten below
// pinResetControl = 43; //Reset control output
//external interrupt enabled pins
//external interrupts could be enalbed in any pin, except same port numbers (PA4,PE4)
pinFlex = PD4; // Flex sensor (Must be external interrupt enabled)
pinTrigger = PD13; //The CAS pin
pinTrigger2 = PD14; //The Cam Sensor pin
case 41:
//Pin mappings as per the v0.4 shield
//Black F407VE http://wiki.stm32duino.com/index.php?title=STM32F407
//PC8~PC12 SDio
//PA9..PA10 Serial1
//PA11..PA12 USB
//PA13..PA15 & PB4 SWD(debug) pins
//PB0 EEPROM CS pin
//PB1 LCD
//PB2 BOOT1
//PB3..PB5 SPI interface
//PB6..PB8 NRF interface
//PD5 & PD6 Serial2
pinInjector1 = PA1; //Output pin injector 1 is on
pinInjector2 = PA2; //Output pin injector 2 is on
pinInjector3 = PA3; //Output pin injector 3 is on
pinInjector4 = PA4; //Output pin injector 4 is on
pinInjector5 = PA5; //Output pin injector 5 is on
pinInjector6 = PD4; //Output pin injector 6 is on
pinCoil1 = PD7; //Pin for coil 1
pinCoil2 = PB9; //Pin for coil 2
pinCoil3 = PA8; //Pin for coil 3
pinCoil4 = PB10; //Pin for coil 4
pinCoil5 = PB11; //Pin for coil 5
pinMAP = PC0; //MAP sensor pin
pinTPS = PC1;//TPS input pin
pinIAT = PC2; //IAT sensor pin
pinCLT = PC3; //CLS sensor pin
pinO2 = PC5; //O2 Sensor pin
pinBat = PB1; //Battery reference voltage pin
pinBaro = PC4;
pinIdle1 = PB12; //Single wire idle control
pinIdle2 = PB11; //2 wire idle control
pinBoost = PC7; //Boost control
pinVVT_1 = PD3; //Default VVT output
pinStepperDir = PE0; //Direction pin for DRV8825 driver
pinStepperStep = PE1; //Step pin for DRV8825 driver
pinStepperEnable = PE2; //Enable pin for DRV8825
pinDisplayReset = PE5; // OLED reset pin
pinFan = PE6; //Pin for the fan output
pinFuelPump = PA6; //Fuel pump output
pinTachOut = PD15; //Tacho output pin
// pinLaunch = 51; //Can be overwritten below
// pinResetControl = 43; //Reset control output
//external interrupt enabled pins
//external interrupts could be enalbed in any pin, except same port numbers (PA4,PE4)
pinFlex = PD4; // Flex sensor (Must be external interrupt enabled)
pinTrigger = PD13; //The CAS pin
pinTrigger2 = PD14; //The Cam Sensor pin
break;
default:
//Pin mappings as per the v0.4 shield
//Black F407VE http://wiki.stm32duino.com/index.php?title=STM32F407
//PC8~PC12 SDio
//PA9..PA10 Serial1
//PA11..PA12 USB
//PA13..PA15 & PB4 SWD(debug) pins
//PB0 EEPROM CS pin
//PB1 LCD
//PB2 BOOT1
//PB3..PB5 SPI interface
//PB6..PB8 NRF interface
//PD5 & PD6 Serial2
pinInjector1 = PA1; //Output pin injector 1 is on
pinInjector2 = PA2; //Output pin injector 2 is on
pinInjector3 = PA3; //Output pin injector 3 is on
pinInjector4 = PA4; //Output pin injector 4 is on
pinInjector5 = PA5; //Output pin injector 5 is on
pinInjector6 = PD4; //Output pin injector 6 is on
pinCoil1 = PD7; //Pin for coil 1
pinCoil2 = PB9; //Pin for coil 2
pinCoil3 = PA8; //Pin for coil 3
pinCoil4 = PB10; //Pin for coil 4
pinCoil5 = PB11; //Pin for coil 5
pinMAP = PC0; //MAP sensor pin
pinTPS = PC1;//TPS input pin
pinIAT = PC2; //IAT sensor pin
pinCLT = PC3; //CLS sensor pin
pinO2 = PC5; //O2 Sensor pin
pinBat = PB1; //Battery reference voltage pin
pinBaro = PC4;
pinIdle1 = PB12; //Single wire idle control
pinIdle2 = PB11; //2 wire idle control
pinBoost = PC7; //Boost control
pinVVT_1 = PD3; //Default VVT output
pinStepperDir = PE0; //Direction pin for DRV8825 driver
pinStepperStep = PE1; //Step pin for DRV8825 driver
pinStepperEnable = PE2; //Enable pin for DRV8825
pinDisplayReset = PE5; // OLED reset pin
pinFan = PE6; //Pin for the fan output
pinFuelPump = PA6; //Fuel pump output
pinTachOut = PD15; //Tacho output pin
// pinLaunch = 51; //Can be overwritten below
// pinResetControl = 43; //Reset control output
//external interrupt enabled pins
//external interrupts could be enalbed in any pin, except same port numbers (PA4,PE4)
pinFlex = PD4; // Flex sensor (Must be external interrupt enabled)
pinTrigger = PD13; //The CAS pin
pinTrigger2 = PD14; //The Cam Sensor pin
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
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);
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);
//Set default values
digitalWrite(pinMAP, HIGH);
//digitalWrite(pinO2, LOW);
digitalWrite(pinTPS, LOW);
}
#endif

View File

@ -259,5 +259,752 @@ uint16_t freeRam()
// The difference is the free, available ram. // The difference is the free, available ram.
return (uint16_t)stackTop - heapTop; return (uint16_t)stackTop - heapTop;
} }
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
//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 = PB5; //Pin for coil 1
pinCoil2 = PB6; //Pin for coil 2
pinCoil3 = PB7; //Pin for coil 3
pinCoil4 = PB8; //Pin for coil 4
pinCoil5 = PB9; //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 = A10;
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 = PA6; //Fuel pump output
pinTachOut = PA7; //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:
#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
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
}
#endif #endif

View File

@ -32,9 +32,9 @@
#define LED_BUILTIN PB1 //Maple Mini #define LED_BUILTIN PB1 //Maple Mini
#endif #endif
#elif defined(ARDUINO_BLACK_F407VE) || defined(STM32F4) #elif defined(ARDUINO_BLACK_F407VE) || defined(STM32F4)
#define BOARD_H "board_stm32F407VE.h"
#define BOARD_DIGITAL_GPIO_PINS 80 #define BOARD_DIGITAL_GPIO_PINS 80
#define BOARD_NR_GPIO_PINS 80 #define BOARD_NR_GPIO_PINS 80
#define LED_BUILTIN PA7
//These boards always make 8/8 channels available //These boards always make 8/8 channels available
#undef INJ_CHANNELS #undef INJ_CHANNELS

View File

@ -11,7 +11,7 @@ unsigned long divu100(unsigned long);
//This is a dedicated function that specifically handles the case of mapping 0-1023 values into a 0 to X range //This is a dedicated function that specifically handles the case of mapping 0-1023 values into a 0 to X range
//This is a common case because it means converting from a standard 10-bit analog input to a byte or 10-bit analog into 0-511 (Eg the temperature readings) //This is a common case because it means converting from a standard 10-bit analog input to a byte or 10-bit analog into 0-511 (Eg the temperature readings)
#if defined(_VARIANT_ARDUINO_STM32_) //libmaple #if defined(_VARIANT_ARDUINO_STM32_) //libmaple //ST stm32duino core returns 0 - 1023 for analog read first use analogReadResolution(12); to make it 12 bit
#define fastMap1023toX(x, out_max) ( ((unsigned long)x * out_max) >> 12) #define fastMap1023toX(x, out_max) ( ((unsigned long)x * out_max) >> 12)
//This is a new version that allows for out_min //This is a new version that allows for out_min
#define fastMap10Bit(x, out_min, out_max) ( ( ((unsigned long)x * (out_max-out_min)) >> 12 ) + out_min) #define fastMap10Bit(x, out_min, out_max) ( ( ((unsigned long)x * (out_max-out_min)) >> 12 ) + out_min)

View File

@ -48,8 +48,8 @@ void initialiseADC()
BIT_CLEAR(ADCSRA,ADPS1); BIT_CLEAR(ADCSRA,ADPS1);
BIT_CLEAR(ADCSRA,ADPS0); BIT_CLEAR(ADCSRA,ADPS0);
#endif #endif
#elif defined(ARDUINO_ARCH_STM32) //STM32GENERIC lib #elif defined(ARDUINO_ARCH_STM32) //STM32GENERIC core and ST STM32duino core, change analog read to 12 bit
analogReadResolution(10); //use 10bits for analog analogReadResolution(12); //use 12bits for analog reading on STM32 boards
#endif #endif
MAPcurRev = 0; MAPcurRev = 0;
MAPcount = 0; MAPcount = 0;

View File

@ -0,0 +1,76 @@
#if defined(ARDUINO_BLACK_F407VE)
#include "BackupSramAsEEPROM.h"
BackupSramAsEEPROM::BackupSramAsEEPROM(){
//Enable the power interface clock
RCC->APB1ENR |= RCC_APB1ENR_PWREN;
//Enable the backup SRAM clock by setting BKPSRAMEN bit i
RCC->AHB1ENR |= RCC_AHB1ENR_BKPSRAMEN;
/** enable the backup regulator (used to maintain the backup SRAM content in
* standby and Vbat modes). NOTE : this bit is not reset when the device
* wakes up from standby, system reset or power reset. You can check that
* the backup regulator is ready on PWR->CSR.brr, see rm p144 */
//enable backup power regulator this makes sram backup posible. bit is not reset by software!
PWR->CSR |= PWR_CSR_BRE;
}
int8_t BackupSramAsEEPROM::write_byte( uint8_t *data, uint16_t bytes, uint16_t offset ) {
uint8_t* base_addr = (uint8_t *) BKPSRAM_BASE;
uint16_t i;
if( bytes + offset >= backup_size ) {
/* ERROR : the last byte is outside the backup SRAM region */
return -1;
}
/* disable backup domain write protection */
//Set the Disable Backup Domain write protection (DBP) bit in PWR power control register
PWR->CR |= PWR_CR_DBP;
for( i = 0; i < bytes; i++ ) {
*(base_addr + offset + i) = *(data + i);
}
//Enable write protection backup sram when finished
PWR->CR &= ~PWR_CR_DBP;
return 0;
}
int8_t BackupSramAsEEPROM::read_byte( uint8_t *data, uint16_t bytes, uint16_t offset ) {
uint8_t* base_addr = (uint8_t *) BKPSRAM_BASE;
uint16_t i;
if( bytes + offset >= backup_size ) {
/* ERROR : the last byte is outside the backup SRAM region */
return -1;
}
for( i = 0; i < bytes; i++ ) {
*(data + i) = *(base_addr + offset + i);
}
return 0;
}
uint8_t BackupSramAsEEPROM::read(uint16_t address) {
uint8_t val = 0;
read_byte(&val, 1, address);
return val;
}
int8_t BackupSramAsEEPROM::write(uint16_t address, uint8_t val) {
write_byte(&val, 1, address);
return 0;
}
int8_t BackupSramAsEEPROM::update(uint16_t address, uint8_t val) {
write_byte(&val, 1, address);
return 0;
}
BackupSramAsEEPROM EEPROM;
#endif

View File

@ -0,0 +1,32 @@
//Backup sram stores data in the battery backuped sram portion.
//The backup battery is available on the ebay stm32F407VET6 black boards.
#if defined(ARDUINO_BLACK_F407VE)
//UGLY HACK TO PREVENT EEPROM LIBRARY BEING IMPORTED FIRST!!
//Use with black_F407VE board
#ifndef EEPROM_h
#define EEPROM_h
#include <stdint.h>
#include "stm32f407xx.h"
class BackupSramAsEEPROM {
private:
const uint16_t backup_size = 0x4000; //maximum of 4kb backuped sram available.
int8_t write_byte( uint8_t *data, uint16_t bytes, uint16_t offset );
int8_t read_byte( uint8_t *data, uint16_t bytes, uint16_t offset );
public:
BackupSramAsEEPROM();
uint8_t read(uint16_t address);
int8_t write(uint16_t address, uint8_t val);
int8_t update(uint16_t address, uint8_t val);
};
extern BackupSramAsEEPROM EEPROM;
#endif
#endif

View File

@ -0,0 +1,415 @@
/*
Copyright (c) 2017 Daniel Fekete
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in all
copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
SOFTWARE.
*/
#include "HardwareTimer.h"
//#include CHIP_PERIPHERAL_INCLUDE
HardwareTimer *interruptTimers[18];
void (*pwm_callback_func)();
static void handleInterrupt(HardwareTimer *timer);
static const uint32_t OCMODE_NOT_USED = 0xFFFF;
HardwareTimer::HardwareTimer(TIM_TypeDef* timer) {
// this->tim_pin_list = pin_list;
// this->tim_pin_list_size = pin_list_size;
_timer.timer = timer;
//handle.Instance = timer;
// for(int i=0; i<4; i++) {
// channelOC[i].OCMode = OCMODE_NOT_USED;
// channelOC[i].OCPolarity = TIM_OCPOLARITY_HIGH;
// channelOC[i].OCNPolarity = TIM_OCNPOLARITY_HIGH;
// channelOC[i].OCFastMode = TIM_OCFAST_DISABLE;
// channelOC[i].OCIdleState = TIM_OCIDLESTATE_RESET;
// channelOC[i].OCNIdleState = TIM_OCNIDLESTATE_RESET;
// channelIC[i].ICPolarity = OCMODE_NOT_USED;
// channelIC[i].ICSelection = TIM_ICSELECTION_DIRECTTI;
// channelIC[i].ICPrescaler = TIM_ICPSC_DIV1;
// channelIC[i].ICFilter = 0;
// }
}
void HardwareTimer::pause() {
HAL_TIM_Base_Stop(&(_timer.handle));
}
void HardwareTimer::resume() {
HAL_TIM_Base_MspInit(_timer)
handle.Init.CounterMode = TIM_COUNTERMODE_UP;
handle.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
handle.Init.RepetitionCounter = 0;
HAL_TIM_Base_Init(&handle);
if (callbacks[0] != NULL) {
HAL_TIM_Base_Start_IT(&handle);
} else {
HAL_TIM_Base_Start(&handle);
}
resumeChannel(1, TIM_CHANNEL_1);
resumeChannel(2, TIM_CHANNEL_2);
resumeChannel(3, TIM_CHANNEL_3);
resumeChannel(4, TIM_CHANNEL_4);
}
void HardwareTimer::resumeChannel(int channel, int timChannel) {
if (channelOC[channel - 1].OCMode != OCMODE_NOT_USED) {
HAL_TIM_OC_ConfigChannel(&handle, &channelOC[channel - 1], timChannel);
if (callbacks[channel] != NULL) {
HAL_TIM_OC_Start_IT(&handle, timChannel);
} else {
HAL_TIM_OC_Start(&handle, timChannel);
}
}
if (channelIC[channel - 1].ICPolarity != OCMODE_NOT_USED) {
HAL_TIM_IC_ConfigChannel(&handle, &channelIC[channel - 1], timChannel);
if (callbacks[channel] != NULL) {
HAL_TIM_IC_Start_IT(&handle, timChannel);
} else {
HAL_TIM_IC_Start(&handle, timChannel);
}
}
}
uint32_t HardwareTimer::getPrescaleFactor() {
return handle.Init.Prescaler;
}
void HardwareTimer::setPrescaleFactor(uint32_t prescaler) {
handle.Init.Prescaler = prescaler;
}
uint32_t HardwareTimer::getOverflow() {
return handle.Init.Period;
}
void HardwareTimer::setOverflow(uint32_t overflow) {
handle.Init.Period = overflow;
}
uint32_t HardwareTimer::getCount(void) {
return __HAL_TIM_GET_COUNTER(&handle);
}
void HardwareTimer::setCount(uint32_t counter) {
__HAL_TIM_SET_COUNTER(&handle, counter);
}
#define MAX_RELOAD ((1 << 16) - 1) // Not always! 32 bit timers!
uint32_t HardwareTimer::getBaseFrequency() {
int freqMul = 2;
int freq2Mul = 2;
uint32_t pFreq = HAL_RCC_GetPCLK1Freq();
#ifdef STM32F1
freq2Mul = 1;
#endif
#ifdef TIM1
if (handle.Instance == TIM1) {
pFreq = HAL_RCC_GetPCLK2Freq();
freqMul = freq2Mul;
}
#endif
#ifdef TIM8
if (handle.Instance == TIM8) {
pFreq = HAL_RCC_GetPCLK2Freq();
freqMul = freq2Mul;
}
#endif
#ifdef TIM9
if (handle.Instance == TIM9) {
pFreq = HAL_RCC_GetPCLK2Freq();
freqMul = freq2Mul;
}
#endif
#ifdef TIM10
if (handle.Instance == TIM10) {
pFreq = HAL_RCC_GetPCLK2Freq();
freqMul = freq2Mul;
}
#endif
#ifdef TIM11
if (handle.Instance == TIM11) {
pFreq = HAL_RCC_GetPCLK2Freq();
freqMul = freq2Mul;
}
#endif
return pFreq * freqMul;
}
uint32_t HardwareTimer::setPeriod(uint32_t microseconds) {
if (!microseconds) {
this->setPrescaleFactor(1);
this->setOverflow(1);
return this->getOverflow();
}
uint32_t period_cyc = microseconds * (getBaseFrequency() / 1000000); //TODO!
uint32_t prescaler = (uint32_t)(period_cyc / MAX_RELOAD + 1);
uint32_t overflow = (uint32_t)((period_cyc + (prescaler / 2)) / prescaler);
this->setPrescaleFactor(prescaler);
this->setOverflow(overflow);
return overflow;
}
static bool isSameChannel(int channel, uint8_t signal) {
// switch(signal) {
// case TIM_CH1:
// case TIM_CH1N:
// return channel == 1;
// case TIM_CH2:
// case TIM_CH2N:
// return channel == 2;
// case TIM_CH3:
// case TIM_CH3N:
// return channel == 3;
// case TIM_CH4:
// case TIM_CH4N:
// return channel == 4;
// }
return false;
}
static const uint32_t PIN_NOT_USED = 0xFF;
void HardwareTimer::setMode(int channel, TIMER_MODES mode, uint8_t pin) {
int pinMode = PIN_NOT_USED;
int pull = GPIO_NOPULL;
switch(mode) {
case TIMER_PWM:
channelOC[channel - 1].OCMode = TIM_OCMODE_PWM1;
pinMode = GPIO_MODE_AF_PP;
break;
case TIMER_OUTPUT_COMPARE:
channelOC[channel - 1].OCMode = TIM_OCMODE_TIMING;
break;
case TIMER_OUTPUT_COMPARE_ACTIVE:
channelOC[channel - 1].OCMode = TIM_OCMODE_ACTIVE;
pinMode = GPIO_MODE_AF_PP;
break;
case TIMER_OUTPUT_COMPARE_INACTIVE:
channelOC[channel - 1].OCMode = TIM_OCMODE_ACTIVE;
pinMode = GPIO_MODE_AF_PP;
break;
case TIMER_OUTPUT_COMPARE_TOGGLE:
channelOC[channel - 1].OCMode = TIM_OCMODE_TOGGLE;
pinMode = GPIO_MODE_AF_PP;
break;
case TIMER_OUTPUT_COMPARE_PWM1:
channelOC[channel - 1].OCMode = TIM_OCMODE_PWM1;
pinMode = GPIO_MODE_AF_PP;
break;
case TIMER_OUTPUT_COMPARE_PWM2:
channelOC[channel - 1].OCMode = TIM_OCMODE_PWM2;
pinMode = GPIO_MODE_AF_PP;
break;
case TIMER_OUTPUT_COMPARE_FORCED_ACTIVE:
channelOC[channel - 1].OCMode = TIM_OCMODE_FORCED_ACTIVE;
pinMode = GPIO_MODE_AF_PP;
break;
case TIMER_OUTPUT_COMPARE_FORCED_INACTIVE:
channelOC[channel - 1].OCMode = TIM_OCMODE_FORCED_INACTIVE;
pinMode = GPIO_MODE_AF_PP;
break;
case TIMER_INPUT_CAPTURE_RISING:
channelIC[channel - 1].ICPolarity = TIM_INPUTCHANNELPOLARITY_RISING;
pinMode = GPIO_MODE_AF_PP;
pull = GPIO_PULLDOWN;
break;
case TIMER_INPUT_CAPTURE_FALLING:
channelIC[channel - 1].ICPolarity = TIM_INPUTCHANNELPOLARITY_FALLING;
pinMode = GPIO_MODE_AF_PP;
pull = GPIO_PULLDOWN;
break;
}
if (pinMode != PIN_NOT_USED) {
//for(int i=0; i<tim_pin_list_size; i++) {
//if (isSameChannel(channel, tim_pin_list[i].signalType)) {
// if (pin == TIMER_DEFAULT_PIN ||
// (variant_pin_list[pin].port == tim_pin_list[i].port && variant_pin_list[pin].pin_mask == tim_pin_list[i].pinMask)) {
// stm32GpioClockEnable(tim_pin_list[i].port);
// GPIO_InitTypeDef GPIO_InitStruct;
// GPIO_InitStruct.Pin = tim_pin_list[i].pinMask;
// GPIO_InitStruct.Mode = pinMode;
// GPIO_InitStruct.Pull = pull;
// GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
// #ifdef STM32F1
// tim_pin_list[i].alternate();
// #else
// GPIO_InitStruct.Alternate = tim_pin_list[i].alternate;
// #endif
// HAL_GPIO_Init(tim_pin_list[i].port, &GPIO_InitStruct);
// return;
// }
//}
//}
}
}
void HardwareTimer::setCompare(int channel, uint32_t compare) {
channelOC[channel - 1].Pulse = compare;
}
uint32_t HardwareTimer::getCompare(int channel) {
if (channel == 1) return __HAL_TIM_GET_COMPARE(&handle, TIM_CHANNEL_1);
if (channel == 2) return __HAL_TIM_GET_COMPARE(&handle, TIM_CHANNEL_2);
if (channel == 3) return __HAL_TIM_GET_COMPARE(&handle, TIM_CHANNEL_3);
if (channel == 4) return __HAL_TIM_GET_COMPARE(&handle, TIM_CHANNEL_4);
return 0;
}
void HardwareTimer::attachInterrupt(void (*callback)(void)) {
callbacks[0] = callback;
}
void HardwareTimer::detachInterrupt() {
callbacks[0] = NULL;
}
void HardwareTimer::attachInterrupt(int channel, void (*callback)(void)) {
callbacks[channel] = callback;
}
void HardwareTimer::detachInterrupt(int channel) {
callbacks[channel] = NULL;
}
void HardwareTimer::refresh() {
HAL_TIM_GenerateEvent(&handle, TIM_EVENTSOURCE_UPDATE);
}
static void handleInterrupt(HardwareTimer *timer) {
if(__HAL_TIM_GET_FLAG(&timer->handle, TIM_FLAG_UPDATE) != RESET) {
__HAL_TIM_CLEAR_IT(&timer->handle, TIM_IT_UPDATE);
if (timer->callbacks[0] != NULL) timer->callbacks[0]();
}
if(__HAL_TIM_GET_FLAG(&timer->handle, TIM_FLAG_CC1) != RESET) {
__HAL_TIM_CLEAR_IT(&timer->handle, TIM_IT_CC1);
if (timer->callbacks[1] != NULL) timer->callbacks[1]();
}
if(__HAL_TIM_GET_FLAG(&timer->handle, TIM_FLAG_CC2) != RESET) {
__HAL_TIM_CLEAR_IT(&timer->handle, TIM_IT_CC2);
if (timer->callbacks[2] != NULL) timer->callbacks[2]();
}
if(__HAL_TIM_GET_FLAG(&timer->handle, TIM_FLAG_CC3) != RESET) {
__HAL_TIM_CLEAR_IT(&timer->handle, TIM_IT_CC3);
if (timer->callbacks[3] != NULL) timer->callbacks[3]();
}
if(__HAL_TIM_GET_FLAG(&timer->handle, TIM_FLAG_CC4) != RESET) {
__HAL_TIM_CLEAR_IT(&timer->handle, TIM_IT_CC4);
if (timer->callbacks[4] != NULL) timer->callbacks[4]();
}
}
#ifdef TIM1
HardwareTimer Timer1(TIM1);
#endif
#ifdef TIM2
HardwareTimer Timer2(TIM2);
#endif
#ifdef TIM3
HardwareTimer Timer3(TIM3);
#endif
#ifdef TIM4
HardwareTimer Timer4(TIM4);
#endif
#ifdef TIM5
HardwareTimer Timer5(TIM5);
#endif
#ifdef TIM8
HardwareTimer Timer8(TIM8);
#endif
//Timer interrupts:
// extern "C" void TIM1_CC_IRQHandler(void) {
// if (interruptTimers[0] != NULL) handleInterrupt(interruptTimers[0]);
// }
// extern "C" void TIM1_UP_IRQHandler(void) {
// if (interruptTimers[0] != NULL) handleInterrupt(interruptTimers[0]);
// }
// #ifndef TIM1_UP_TIM10_IRQHandler
// extern "C" void TIM1_UP_TIM10_IRQHandler(void) {
// if (interruptTimers[0] != NULL) handleInterrupt(interruptTimers[0]);
// if (interruptTimers[9] != NULL) handleInterrupt(interruptTimers[9]);
// }
// #endif
// in stm32_PWM.c
/*
extern "C" void TIM2_IRQHandler(void) {
handleInterrupt(interruptTimers[1]);
}*/
// extern "C" void TIM3_IRQHandler(void) {
// if (interruptTimers[2] != NULL) handleInterrupt(interruptTimers[2]);
// }
// extern "C" void TIM4_IRQHandler(void) {
// if (interruptTimers[3] != NULL) handleInterrupt(interruptTimers[3]);
// }

View File

@ -0,0 +1,123 @@
#ifndef HARDWARETIMER_H_
#define HARDWARETIMER_H_
#include "Arduino.h"
#include "timer.h"
//#include "stm32_gpio_af.h"
typedef enum {
//libmaple: // HAL compatible
TIMER_DISABLED,
TIMER_PWM, // == TIM_OCMODE_PWM1
TIMER_OUTPUT_COMPARE, // == TIM_OCMODE_TIMING no output, useful for only-interrupt
//other:
TIMER_OUTPUT_COMPARE_ACTIVE, // == TIM_OCMODE_ACTIVE pin is set high when counter == channel compare
TIMER_OUTPUT_COMPARE_INACTIVE, // == TIM_OCMODE_INACTIVE pin is set low when counter == channel compare
TIMER_OUTPUT_COMPARE_TOGGLE, // == TIM_OCMODE_TOGGLE pin toggles when counter == channel compare
TIMER_OUTPUT_COMPARE_PWM1, // == TIM_OCMODE_PWM1 pin high when counter < channel compare, low otherwise
TIMER_OUTPUT_COMPARE_PWM2, // == TIM_OCMODE_PWM2 pin low when counter < channel compare, high otherwise
TIMER_OUTPUT_COMPARE_FORCED_ACTIVE, // == TIM_OCMODE_FORCED_ACTIVE pin always high
TIMER_OUTPUT_COMPARE_FORCED_INACTIVE, // == TIM_OCMODE_FORCED_INACTIVE pin always low
//Input capture
TIMER_INPUT_CAPTURE_RISING, // == TIM_INPUTCHANNELPOLARITY_RISING
TIMER_INPUT_CAPTURE_FALLING, // == TIM_INPUTCHANNELPOLARITY_FALLING
//PWM input capture on channel 1 + channel 2
//TIMER_INPUT_CAPTURE_PWM, // == TIM_INPUTCHANNELPOLARITY_RISING (channel 1) + TIM_INPUTCHANNELPOLARITY_FALLING (channel 2)
//Encoder mode
//TIMER_ENCODER // == TIM_ENCODERMODE_TI1
} TIMER_MODES;
#define TIMER_DEFAULT_PIN 0xFF
class HardwareTimer {
public:
HardwareTimer(TIM_TypeDef* timer);
void pause(void);
void resume(void);
uint32_t getPrescaleFactor();
void setPrescaleFactor(uint32_t factor);
uint32_t getOverflow();
void setOverflow(uint32_t val);
uint32_t getCount(void);
void setCount(uint32_t val);
uint32_t setPeriod(uint32_t microseconds);
void setMode(int channel, TIMER_MODES mode, uint8_t pin = TIMER_DEFAULT_PIN);
uint32_t getCompare(int channel);
void setCompare(int channel, uint32_t compare);
//Add interrupt to period update
void attachInterrupt(void (*handler)(void));
void detachInterrupt();
//Add interrupt to channel
void attachInterrupt(int channel, void (*handler)(void));
void detachInterrupt(int channel);
void refresh(void);
uint32_t getBaseFrequency();
TIM_HandleTypeDef handle = {0};
TIM_OC_InitTypeDef channelOC[4];
TIM_IC_InitTypeDef channelIC[4];
//Callbacks: 0 for update, 1-4 for channels
void (*callbacks[5])(void);
stimer_t _timer;
// //const stm32_tim_pin_list_type *tim_pin_list;
// int tim_pin_list_size;
private:
void resumeChannel(int channel, int timChannel);
};
#ifdef TIM1
extern HardwareTimer Timer1;
#endif
#ifdef TIM2
extern HardwareTimer Timer2;
#endif
#ifdef TIM3
extern HardwareTimer Timer3;
#endif
#ifdef TIM4
extern HardwareTimer Timer4;
#endif
#ifdef TIM5
extern HardwareTimer Timer5;
#endif
#ifdef TIM8
extern HardwareTimer Timer8;
#endif
#endif

View File

@ -10,12 +10,15 @@ A full copy of the license may be found in the projects root directory
#include "comms.h" #include "comms.h"
#if defined(CORE_SAMD21) #if defined(CORE_SAMD21)
#include "src/FlashStorage/FlashAsEEPROM.h" #include "src/FlashStorage/FlashAsEEPROM.h"
#elif defined(ARDUINO_BLACK_F407VE)
#include "src/BackupSram/BackupSramAsEEPROM.h"
#elif defined(CORE_STM32) #elif defined(CORE_STM32)
#include <Fram.h> #include <Fram.h>
#else #else
#include <EEPROM.h> #include <EEPROM.h>
#endif #endif
#include "storage.h" #include "storage.h"
void writeAllConfig() void writeAllConfig()
{ {
writeConfig(veSetPage); writeConfig(veSetPage);
@ -656,4 +659,4 @@ byte readLastBaro() { return EEPROM.read(EEPROM_LAST_BARO); }
void storeLastBaro(byte newValue) { EEPROM.update(EEPROM_LAST_BARO, newValue); } void storeLastBaro(byte newValue) { EEPROM.update(EEPROM_LAST_BARO, newValue); }
void storeCalibrationValue(uint16_t location, byte value) { EEPROM.update(location, value); } //This is essentially just an abstraction for EEPROM.update() void storeCalibrationValue(uint16_t location, byte value) { EEPROM.update(location, value); } //This is essentially just an abstraction for EEPROM.update()
byte readEEPROMVersion() { return EEPROM.read(EEPROM_DATA_VERSION); } byte readEEPROMVersion() { return EEPROM.read(EEPROM_DATA_VERSION); }
void storeEEPROMVersion(byte newVersion) { EEPROM.update(EEPROM_DATA_VERSION, newVersion); } void storeEEPROMVersion(byte newVersion) { EEPROM.update(EEPROM_DATA_VERSION, newVersion); }

View File

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