Updated STM work
This commit is contained in:
parent
32e6cc9a2e
commit
fc577c9a59
|
@ -901,10 +901,9 @@ void sendPage(bool useChar)
|
|||
for (byte x = 0; x < npage_size[currentPage]; x++)
|
||||
{
|
||||
response[x] = *((byte *)pnt_configPage + x); //Each byte is simply the location in memory of the configPage + the offset + the variable number (x)
|
||||
//if ( (x & 31) == 1) { loop(); } //Every 32 loops, do a manual call to loop() to ensure that there is no misses
|
||||
}
|
||||
|
||||
Serial.write((byte *)&response, sizeof(response));
|
||||
Serial.write((byte *)&response, npage_size[currentPage]);
|
||||
// }
|
||||
}
|
||||
return;
|
||||
|
@ -958,9 +957,9 @@ void receiveCalibration(byte tableID)
|
|||
bool every2nd = true;
|
||||
int x;
|
||||
int counter = 0;
|
||||
pinMode(13, OUTPUT);
|
||||
pinMode(LED_BUILTIN, OUTPUT); //pinMode(13, OUTPUT);
|
||||
|
||||
digitalWrite(13, LOW);
|
||||
digitalWrite(LED_BUILTIN, LOW); //digitalWrite(13, LOW);
|
||||
for (x = 0; x < 1024; x++)
|
||||
{
|
||||
//UNlike what is listed in the protocol documentation, the O2 sensor values are sent as bytes rather than ints
|
||||
|
@ -996,7 +995,11 @@ void receiveCalibration(byte tableID)
|
|||
EEPROM.update(y, (byte)tempValue);
|
||||
|
||||
every2nd = false;
|
||||
analogWrite(13, (counter % 50) );
|
||||
#if defined(CORE_STM32)
|
||||
digitalWrite(LED_BUILTIN, !digitalRead(LED_BUILTIN));
|
||||
#else
|
||||
analogWrite(LED_BUILTIN, (counter % 50) ); //analogWrite(13, (counter % 50) );
|
||||
#endif
|
||||
counter++;
|
||||
}
|
||||
else {
|
||||
|
@ -1149,4 +1152,4 @@ void commandButtons()
|
|||
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -4,11 +4,14 @@
|
|||
#include "table.h"
|
||||
|
||||
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) || defined(__AVR_ATmega2561__)
|
||||
#define BOARD_NR_GPIO_PINS 54
|
||||
#define LED_BUILTIN 13
|
||||
#define CORE_AVR
|
||||
#elif defined(CORE_TEENSY)
|
||||
//Currently nothing to do here
|
||||
#elif defined(STM32_MCU_SERIES)
|
||||
#define BOARD_NR_GPIO_PINS 34
|
||||
#elif defined(STM32_MCU_SERIES) || defined(_VARIANT_ARDUINO_STM32_)
|
||||
#define CORE_STM32
|
||||
#define LED_BUILTIN 33
|
||||
|
||||
inline unsigned char digitalPinToInterrupt(unsigned char Interrupt_pin) { return Interrupt_pin; } //This isn't included in the stm32duino libs (yet)
|
||||
#define portOutputRegister(port) (volatile byte *)( &(port->regs->ODR) ) //These are defined in STM32F1/variants/generic_stm32f103c/variant.h but return a non byte* value
|
||||
|
@ -103,7 +106,7 @@ const char TSfirmwareVersion[] = "Speeduino 2016.09";
|
|||
|
||||
const byte data_structure_version = 2; //This identifies the data structure when reading / writing.
|
||||
const byte page_size = 64;
|
||||
const int npage_size[11] ={0,288,64,288,64,288,64,64,160,192,128};
|
||||
const int npage_size[11] = {0,288,64,288,64,288,64,64,160,192,128};
|
||||
//const byte page10_size = 128;
|
||||
const int map_page_size = 288;
|
||||
|
||||
|
@ -704,4 +707,4 @@ extern byte iatCalibrationTable[CALIBRATION_TABLE_SIZE];
|
|||
extern byte o2CalibrationTable[CALIBRATION_TABLE_SIZE];
|
||||
|
||||
|
||||
#endif // GLOBALS_H
|
||||
#endif // GLOBALS_H
|
||||
|
|
|
@ -159,13 +159,13 @@ See page 136 of the processors datasheet: http://www.atmel.com/Images/doc2549.pd
|
|||
//Hack compatibility with AVR timers that run at different speeds
|
||||
#define uS_TO_TIMER_COMPARE_SLOW(uS) ((uS * 15) >> 5)
|
||||
|
||||
#elif defined(STM32_MCU_SERIES)
|
||||
#elif defined(CORE_STM32)
|
||||
//Placeholders ONLY!
|
||||
|
||||
//https://github.com/rogerclarkmelbourne/Arduino_STM32/blob/master/STM32F4/cores/maple/libmaple/timer.h#L51
|
||||
#define MAX_TIMER_PERIOD 139808 // 2.13333333uS * 65535
|
||||
#define uS_TO_TIMER_COMPARE(uS) ((uS * 15) >> 5) //Converts a given number of uS into the required number of timer ticks until that time has passed.
|
||||
#define uS_TO_TIMER_COMPARE_SLOW(uS) ((uS * 15) >> 5) //Converts a given number of uS into the required number of timer ticks until that time has passed.
|
||||
#define MAX_TIMER_PERIOD 131070 //The longest period of time (in uS) that the timer can permit (IN this case it is 65535 * 2, as each timer tick is 2uS)
|
||||
#define uS_TO_TIMER_COMPARE(uS) (uS >> 1) //Converts a given number of uS into the required number of timer ticks until that time has passed.
|
||||
#define uS_TO_TIMER_COMPARE_SLOW(uS) (uS >> 1) //Converts a given number of uS into the required number of timer ticks until that time has passed.
|
||||
|
||||
#define FUEL1_COUNTER (TIMER2->regs).gen->CNT
|
||||
#define FUEL2_COUNTER (TIMER2->regs).gen->CNT
|
||||
|
@ -232,6 +232,20 @@ void setIgnitionSchedule6(void (*startCallback)(), unsigned long timeout, unsign
|
|||
void setIgnitionSchedule7(void (*startCallback)(), unsigned long timeout, unsigned long duration, void(*endCallback)());
|
||||
void setIgnitionSchedule8(void (*startCallback)(), unsigned long timeout, unsigned long duration, void(*endCallback)());
|
||||
|
||||
//Needed for STM32 interrupt handlers
|
||||
#if defined(CORE_STM32)
|
||||
static inline void fuelSchedule1Interrupt();
|
||||
static inline void fuelSchedule2Interrupt();
|
||||
static inline void fuelSchedule3Interrupt();
|
||||
static inline void fuelSchedule4Interrupt();
|
||||
static inline void fuelSchedule5Interrupt();
|
||||
static inline void ignitionSchedule1Interrupt();
|
||||
static inline void ignitionSchedule2Interrupt();
|
||||
static inline void ignitionSchedule3Interrupt();
|
||||
static inline void ignitionSchedule4Interrupt();
|
||||
static inline void ignitionSchedule5Interrupt();
|
||||
#endif
|
||||
|
||||
enum ScheduleStatus {OFF, PENDING, RUNNING}; //The 3 statuses that a schedule can have
|
||||
|
||||
struct Schedule {
|
||||
|
@ -336,4 +350,4 @@ static inline unsigned int popQueue(volatile Schedule *queue[])
|
|||
}
|
||||
|
||||
|
||||
#endif // SCHEDULER_H
|
||||
#endif // SCHEDULER_H
|
||||
|
|
|
@ -160,8 +160,31 @@ void initialiseSchedulers()
|
|||
NVIC_ENABLE_IRQ(IRQ_FTM1);
|
||||
|
||||
#elif defined(CORE_STM32)
|
||||
//(TIMER2->regs).gen->CCMR1 &= ~TIM_CCMR1_OC1M; //Select channel 1 output Compare and Mode
|
||||
//see https://github.com/rogerclarkmelbourne/Arduino_STM32/blob/754bc2969921f1ef262bd69e7faca80b19db7524/STM32F1/system/libmaple/include/libmaple/timer.h#L444
|
||||
(TIMER1->regs).bas->PSC = (TIMER2->regs).bas->PSC = (TIMER3->regs).bas->PSC = (CYCLES_PER_MICROSECOND << 1) - 1; //2us resolution
|
||||
//TimerX.setPrescaleFactor(CYCLES_PER_MICROSECOND * 2U); //2us resolution
|
||||
|
||||
Timer2.setMode(TIMER_CH1, TIMER_OUTPUT_COMPARE);
|
||||
Timer2.setMode(TIMER_CH2, TIMER_OUTPUT_COMPARE);
|
||||
Timer2.setMode(TIMER_CH3, TIMER_OUTPUT_COMPARE);
|
||||
Timer2.setMode(TIMER_CH4, TIMER_OUTPUT_COMPARE);
|
||||
|
||||
Timer3.setMode(TIMER_CH1, TIMER_OUTPUT_COMPARE);
|
||||
Timer3.setMode(TIMER_CH2, TIMER_OUTPUT_COMPARE);
|
||||
Timer3.setMode(TIMER_CH3, TIMER_OUTPUT_COMPARE);
|
||||
Timer3.setMode(TIMER_CH4, TIMER_OUTPUT_COMPARE);
|
||||
|
||||
Timer2.attachInterrupt(1, fuelSchedule1Interrupt);
|
||||
Timer2.attachInterrupt(2, fuelSchedule2Interrupt);
|
||||
Timer2.attachInterrupt(3, fuelSchedule3Interrupt);
|
||||
Timer2.attachInterrupt(4, fuelSchedule4Interrupt);
|
||||
|
||||
Timer3.attachInterrupt(1, ignitionSchedule1Interrupt);
|
||||
Timer3.attachInterrupt(2, ignitionSchedule2Interrupt);
|
||||
Timer3.attachInterrupt(3, ignitionSchedule3Interrupt);
|
||||
Timer3.attachInterrupt(4, ignitionSchedule4Interrupt);
|
||||
|
||||
//(TIMER2->regs).gen->CCMR1 &= ~TIM_CCMR1_OC1M; //Select channel 1 output Compare and Mode
|
||||
//TIM3->CR1 |= TIM_CR1_CEN
|
||||
|
||||
#endif
|
||||
|
@ -652,4 +675,4 @@ void ftm0_isr(void)
|
|||
else if(FTM0_C7SC & FTM_CSC_CHF) { FTM0_C7SC &= ~FTM_CSC_CHF; ignitionSchedule4Interrupt(); }
|
||||
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
|
|
|
@ -22,6 +22,9 @@ Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA.
|
|||
#define engineSquirtsPerCycle 2 //Would be 1 for a 2 stroke
|
||||
//**************************************************************************************************
|
||||
|
||||
//https://developer.mbed.org/handbook/C-Data-Types
|
||||
#include <stdint.h>
|
||||
//************************************************
|
||||
#include "globals.h"
|
||||
#include "utils.h"
|
||||
#include "table.h"
|
||||
|
@ -182,8 +185,10 @@ void setup()
|
|||
|
||||
//Setup the calibration tables
|
||||
loadCalibration();
|
||||
|
||||
//Set the pin mappings
|
||||
setPinMapping(configPage1.pinMapping);
|
||||
if(configPage1.pinMapping > BOARD_NR_GPIO_PINS) { setPinMapping(3); } //First time running? set to v0.4
|
||||
else { setPinMapping(configPage1.pinMapping); }
|
||||
|
||||
//Need to check early on whether the coil charging is inverted. If this is not set straight away it can cause an unwanted spark at bootup
|
||||
if(configPage2.IgInv == 1) { coilHIGH = LOW, coilLOW = HIGH; }
|
||||
|
@ -1471,4 +1476,4 @@ void loop()
|
|||
}
|
||||
} //Ignition schedules on
|
||||
} //Has sync and RPM
|
||||
} //loop()
|
||||
} //loop()
|
||||
|
|
|
@ -39,9 +39,10 @@ void initialiseTimers()
|
|||
lowResTimer.begin(oneMSInterval, 1000);
|
||||
|
||||
#elif defined(CORE_STM32)
|
||||
Timer4.setChannel1Mode(TIMER_OUTPUTCOMPARE);
|
||||
Timer4.setPeriod(1000);
|
||||
Timer4.attachCompare1Interrupt(oneMSInterval);
|
||||
Timer4.setPeriod(1000); // Set up period
|
||||
// Set up an interrupt
|
||||
Timer4.setMode(TIMER_CH1, TIMER_OUTPUT_COMPARE);
|
||||
Timer4.attachInterrupt(1, oneMSInterval);
|
||||
#endif
|
||||
|
||||
dwellLimit_uS = (1000 * configPage2.dwellLimit);
|
||||
|
@ -175,4 +176,4 @@ void oneMSInterval() //Most ARM chips can simply call a function
|
|||
TCNT2 = 131; //Preload timer2 with 100 cycles, leaving 156 till overflow.
|
||||
TIFR2 = 0x00; //Timer2 INT Flag Reg: Clear Timer Overflow Flag
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
|
|
@ -40,19 +40,24 @@ void setPinMapping(byte boardID)
|
|||
{
|
||||
//This is dumb, but it'll do for now to get things compiling
|
||||
#if defined(CORE_STM32)
|
||||
#define A0 0
|
||||
#define A1 1
|
||||
#define A2 2
|
||||
#define A3 3
|
||||
#define A4 4
|
||||
#define A5 5
|
||||
#define A6 6
|
||||
#define A7 7
|
||||
#define A8 8
|
||||
#define A9 9
|
||||
#define A13 13
|
||||
#define A14 14
|
||||
#define A15 15
|
||||
//STM32F1/variants/.../board.cpp
|
||||
#define A0 boardADCPins[0]
|
||||
#define A1 boardADCPins[1]
|
||||
#define A2 boardADCPins[2]
|
||||
#define A3 boardADCPins[3]
|
||||
#define A4 boardADCPins[4]
|
||||
#define A5 boardADCPins[5]
|
||||
#define A6 boardADCPins[6]
|
||||
#define A7 boardADCPins[7]
|
||||
#define A8 boardADCPins[8]
|
||||
#define A9 boardADCPins[9]
|
||||
//STM32F1 have only 9 12bit adc
|
||||
#define A10 boardADCPins[0]
|
||||
#define A11 boardADCPins[1]
|
||||
#define A12 boardADCPins[2]
|
||||
#define A13 boardADCPins[3]
|
||||
#define A14 boardADCPins[4]
|
||||
#define A15 boardADCPins[5]
|
||||
#endif
|
||||
|
||||
switch (boardID)
|
||||
|
@ -158,6 +163,35 @@ void setPinMapping(byte boardID)
|
|||
pinCoil4 = 21;
|
||||
pinCoil3 = 30;
|
||||
pinO2 = A22;
|
||||
#elif defined(CORE_STM32)
|
||||
//http://docs.leaflabs.com/static.leaflabs.com/pub/leaflabs/maple-docs/0.0.12/hardware/maple-mini.html#master-pin-map
|
||||
//pins 23, 24 and 33 couldn't be used
|
||||
pinInjector1 = 15; //Output pin injector 1 is on
|
||||
pinInjector2 = 16; //Output pin injector 2 is on
|
||||
pinInjector3 = 17; //Output pin injector 3 is on
|
||||
pinInjector4 = 18; //Output pin injector 4 is on
|
||||
pinCoil1 = 19; //Pin for coil 1
|
||||
pinCoil2 = 20; //Pin for coil 2
|
||||
pinCoil3 = 21; //Pin for coil 3
|
||||
pinCoil4 = 26; //Pin for coil 4
|
||||
pinCoil5 = 27; //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
|
||||
pinStepperDir = 12; //Direction pin for DRV8825 driver
|
||||
pinStepperStep = 13; //Step pin for DRV8825 driver
|
||||
pinStepperEnable = 14; //Enable pin for DRV8825
|
||||
pinDisplayReset = 2; // OLED reset pin
|
||||
pinFan = 1; //Pin for the fan output
|
||||
pinFuelPump = 0; //Fuel pump output
|
||||
pinTachOut = 31; //Tacho output pin
|
||||
//external interrupt enabled pins
|
||||
pinFlex = 32; // Flex sensor (Must be external interrupt enabled)
|
||||
pinTrigger = 25; //The CAS pin
|
||||
pinTrigger2 = 22; //The Cam Sensor pin
|
||||
#endif
|
||||
break;
|
||||
|
||||
|
@ -205,6 +239,35 @@ void setPinMapping(byte boardID)
|
|||
pinCoil4 = 29;
|
||||
pinCoil3 = 30;
|
||||
pinO2 = A22;
|
||||
#elif defined(CORE_STM32)
|
||||
//http://docs.leaflabs.com/static.leaflabs.com/pub/leaflabs/maple-docs/0.0.12/hardware/maple-mini.html#master-pin-map
|
||||
//pins 23, 24 and 33 couldn't be used
|
||||
pinInjector1 = 15; //Output pin injector 1 is on
|
||||
pinInjector2 = 16; //Output pin injector 2 is on
|
||||
pinInjector3 = 17; //Output pin injector 3 is on
|
||||
pinInjector4 = 18; //Output pin injector 4 is on
|
||||
pinCoil1 = 19; //Pin for coil 1
|
||||
pinCoil2 = 20; //Pin for coil 2
|
||||
pinCoil3 = 21; //Pin for coil 3
|
||||
pinCoil4 = 26; //Pin for coil 4
|
||||
pinCoil5 = 27; //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
|
||||
pinStepperDir = 12; //Direction pin for DRV8825 driver
|
||||
pinStepperStep = 13; //Step pin for DRV8825 driver
|
||||
pinStepperEnable = 14; //Enable pin for DRV8825
|
||||
pinDisplayReset = 2; // OLED reset pin
|
||||
pinFan = 1; //Pin for the fan output
|
||||
pinFuelPump = 0; //Fuel pump output
|
||||
pinTachOut = 31; //Tacho output pin
|
||||
//external interrupt enabled pins
|
||||
pinFlex = 32; // Flex sensor (Must be external interrupt enabled)
|
||||
pinTrigger = 25; //The CAS pin
|
||||
pinTrigger2 = 22; //The Cam Sensor pin
|
||||
#endif
|
||||
break;
|
||||
|
||||
|
@ -374,27 +437,17 @@ void setPinMapping(byte boardID)
|
|||
break;
|
||||
}
|
||||
|
||||
//Setup any devices that are using selectable pins
|
||||
if (configPage3.launchPin != 0) {
|
||||
pinLaunch = configPage3.launchPin;
|
||||
}
|
||||
if (configPage2.ignBypassPin != 0) {
|
||||
pinIgnBypass = configPage2.ignBypassPin;
|
||||
}
|
||||
if (configPage1.tachoPin != 0) {
|
||||
pinTachOut = configPage1.tachoPin;
|
||||
}
|
||||
if (configPage2.fuelPumpPin != 0) {
|
||||
pinFuelPump = configPage2.fuelPumpPin;
|
||||
}
|
||||
if (configPage4.fanPin != 0) {
|
||||
pinFan = configPage4.fanPin;
|
||||
}
|
||||
if (configPage3.boostPin != 0) {
|
||||
pinBoost = configPage3.boostPin;
|
||||
}
|
||||
if (configPage3.vvtPin != 0) {
|
||||
pinVVT_1 = configPage3.vvtPin;
|
||||
//First time running?
|
||||
if (configPage3.launchPin < BOARD_NR_GPIO_PINS)
|
||||
{
|
||||
//Setup any devices that are using selectable pins
|
||||
if (configPage3.launchPin != 0) { pinLaunch = configPage3.launchPin; }
|
||||
if (configPage2.ignBypassPin != 0) { pinIgnBypass = configPage2.ignBypassPin; }
|
||||
if (configPage1.tachoPin != 0) { pinTachOut = configPage1.tachoPin; }
|
||||
if (configPage2.fuelPumpPin != 0) { pinFuelPump = configPage2.fuelPumpPin; }
|
||||
if (configPage4.fanPin != 0) { pinFan = configPage4.fanPin; }
|
||||
if (configPage3.boostPin != 0) { pinBoost = configPage3.boostPin; }
|
||||
if (configPage3.vvtPin != 0) { pinVVT_1 = configPage3.vvtPin; }
|
||||
}
|
||||
|
||||
//Finally, set the relevant pin modes for outputs
|
||||
|
@ -446,13 +499,23 @@ void setPinMapping(byte boardID)
|
|||
tach_pin_mask = digitalPinToBitMask(pinTachOut);
|
||||
|
||||
//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);
|
||||
#if defined(CORE_STM32)
|
||||
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);
|
||||
#else
|
||||
pinMode(pinMAP, INPUT);
|
||||
pinMode(pinO2, INPUT);
|
||||
pinMode(pinO2_2, INPUT);
|
||||
pinMode(pinTPS, INPUT);
|
||||
pinMode(pinIAT, INPUT);
|
||||
pinMode(pinCLT, INPUT);
|
||||
pinMode(pinBat, INPUT);
|
||||
#endif
|
||||
pinMode(pinTrigger, INPUT);
|
||||
pinMode(pinTrigger2, INPUT);
|
||||
pinMode(pinTrigger3, INPUT);
|
||||
|
@ -471,10 +534,13 @@ void setPinMapping(byte boardID)
|
|||
triggerSec_pin_port = portInputRegister(digitalPinToPort(pinTrigger2));
|
||||
triggerSec_pin_mask = digitalPinToBitMask(pinTrigger2);
|
||||
|
||||
//Set default values
|
||||
digitalWrite(pinMAP, HIGH);
|
||||
//digitalWrite(pinO2, LOW);
|
||||
digitalWrite(pinTPS, LOW);
|
||||
#if defined(CORE_STM32)
|
||||
#else
|
||||
//Set default values
|
||||
digitalWrite(pinMAP, HIGH);
|
||||
//digitalWrite(pinO2, LOW);
|
||||
digitalWrite(pinTPS, LOW);
|
||||
#endif
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -540,4 +606,4 @@ unsigned int PW_AN(int REQ_FUEL, byte VE, byte TPS, int corrections, int injOpen
|
|||
TPS = 100;
|
||||
}
|
||||
return PW(REQ_FUEL, VE, currentStatus.MAP, corrections, injOpen);
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue