Fixing last comit

This commit is contained in:
Vitor Moreno B. Sales 2017-08-02 22:51:07 -03:00 committed by GitHub
parent e9db1a2f78
commit d9f38f82de
26 changed files with 1333 additions and 741 deletions

View File

@ -6,6 +6,39 @@ void boostControl();
void vvtControl();
void initialiseFan();
#if defined(CORE_AVR)
#define ENABLE_BOOST_TIMER() TIMSK1 |= (1 << OCIE1A)
#define DISABLE_BOOST_TIMER() TIMSK1 &= ~(1 << OCIE1A)
#define ENABLE_VVT_TIMER() TIMSK1 |= (1 << OCIE1B)
#define DISABLE_VVT_TIMER() TIMSK1 &= ~(1 << OCIE1B)
#define BOOST_TIMER_COMPARE OCR1A
#define BOOST_TIMER_COUNTER TCNT1
#define VVT_TIMER_COMPARE OCR1B
#define VVT_TIMER_COUNTER TCNT1
#elif defined(CORE_TEENSY)
#define ENABLE_BOOST_TIMER() FTM1_C0SC |= FTM_CSC_CHIE
#define DISABLE_BOOST_TIMER() FTM1_C0SC &= ~FTM_CSC_CHIE
#define ENABLE_VVT_TIMER() FTM1_C1SC |= FTM_CSC_CHIE
#define DISABLE_VVT_TIMER() FTM1_C1SC &= ~FTM_CSC_CHIE
#define BOOST_TIMER_COMPARE FTM1_C0V
#define BOOST_TIMER_COUNTER FTM1_CNT
#define VVT_TIMER_COMPARE FTM1_C1V
#define VVT_TIMER_COUNTER FTM1_CNT
#elif defined(CORE_STM32)
#endif
#define BOOST_PIN_LOW() *boost_pin_port &= ~(boost_pin_mask)
#define BOOST_PIN_HIGH() *boost_pin_port |= (boost_pin_mask)
#define VVT_PIN_LOW() *vvt_pin_port &= ~(vvt_pin_mask)
#define VVT_PIN_HIGH() *vvt_pin_port |= (vvt_pin_mask)
volatile byte *boost_pin_port;
volatile byte boost_pin_mask;
volatile byte *vvt_pin_port;

View File

@ -3,7 +3,8 @@ Speeduino - Simple engine management for the Arduino Mega 2560 platform
Copyright (C) Josh Stewart
A full copy of the license may be found in the projects root directory
*/
integerPID boostPID(&MAPx100, &boost_pwm_target_value, &boostTargetx100, configPage3.boostKP, configPage3.boostKI, configPage3.boostKD, DIRECT); //This is the PID object if that algorithm is used. Needs to be global as it maintains state outside of each function call
//integerPID boostPID(&MAPx100, &boost_pwm_target_value, &boostTargetx100, configPage3.boostKP, configPage3.boostKI, configPage3.boostKD, DIRECT); //This is the PID object if that algorithm is used. Needs to be global as it maintains state outside of each function call
integerPIDnew boostPID(&currentStatus.MAP, &boost_pwm_target_value, &boost_cl_target_boost, configPage3.boostKP, configPage3.boostKI, configPage3.boostKD, DIRECT); //This is the PID object if that algorithm is used. Needs to be global as it maintains state outside of each function call
/*
Fan control
@ -28,14 +29,18 @@ void fanControl()
}
}
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
#if defined(CORE_AVR) || defined(CORE_TEENSY)
void initialiseAuxPWM()
{
TCCR1B = 0x00; //Disbale Timer1 while we set it up
TCNT1 = 0; //Reset Timer Count
TIFR1 = 0x00; //Timer1 INT Flag Reg: Clear Timer Overflow Flag
TCCR1A = 0x00; //Timer1 Control Reg A: Wave Gen Mode normal (Simply counts up from 0 to 65535 (16-bit int)
TCCR1B = (1 << CS12); //Timer1 Control Reg B: Timer Prescaler set to 256. 1 tick = 16uS. Refer to http://www.instructables.com/files/orig/F3T/TIKL/H3WSA4V7/F3TTIKLH3WSA4V7.jpg
#if defined(CORE_AVR)
TCCR1B = 0x00; //Disbale Timer1 while we set it up
TCNT1 = 0; //Reset Timer Count
TIFR1 = 0x00; //Timer1 INT Flag Reg: Clear Timer Overflow Flag
TCCR1A = 0x00; //Timer1 Control Reg A: Wave Gen Mode normal (Simply counts up from 0 to 65535 (16-bit int)
TCCR1B = (1 << CS12); //Timer1 Control Reg B: Timer Prescaler set to 256. 1 tick = 16uS. Refer to http://www.instructables.com/files/orig/F3T/TIKL/H3WSA4V7/F3TTIKLH3WSA4V7.jpg
#elif defined(CORE_TEENSY)
//REALLY NEED TO DO THIS!
#endif
boost_pin_port = portOutputRegister(digitalPinToPort(pinBoost));
boost_pin_mask = digitalPinToBitMask(pinBoost);
@ -45,7 +50,7 @@ void initialiseAuxPWM()
boost_pwm_max_count = 1000000L / (16 * configPage3.boostFreq * 2); //Converts the frequency in Hz to the number of ticks (at 16uS) 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 / (16 * configPage3.vvtFreq * 2); //Converts the frequency in Hz to the number of ticks (at 16uS) it takes to complete 1 cycle
//TIMSK1 |= (1 << OCIE1A); <---- Not required as compare A is turned on when needed by boost control
TIMSK1 |= (1 << OCIE1B); //Turn on the B compare unit (ie turn on the interrupt)
ENABLE_VVT_TIMER(); //Turn on the B compare unit (ie turn on the interrupt)
boostPID.SetOutputLimits(percentage(configPage1.boostMinDuty, boost_pwm_max_count) , percentage(configPage1.boostMaxDuty, boost_pwm_max_count));
boostPID.SetTunings(configPage3.boostKP, configPage3.boostKI, configPage3.boostKD);
@ -63,7 +68,8 @@ void boostControl()
{
MAPx100 = currentStatus.MAP * 100;
boost_cl_target_boost = get3DTableValue(&boostTable, currentStatus.TPS, currentStatus.RPM) * 2; //Boost target table is in kpa and divided by 2
if( (boostCounter & 3) == 1) { boost_cl_target_boost = get3DTableValue(&boostTable, currentStatus.TPS, currentStatus.RPM) * 2; } //Boost target table is in kpa and divided by 2
//If flex fuel is enabled, there can be an adder to the boost target based on ethanol content
if( configPage1.flexEnabled == 1 )
{
@ -80,23 +86,25 @@ void boostControl()
boostPID.Compute();
currentStatus.boostDuty = (unsigned long)(boost_pwm_target_value * 100UL) / boost_pwm_max_count;
TIMSK1 |= (1 << OCIE1A); //Turn on the compare unit (ie turn on the interrupt)
if(currentStatus.boostDuty == 0) { DISABLE_BOOST_TIMER(); BOOST_PIN_LOW(); } //If boost duty is 0, shut everything down
else { ENABLE_BOOST_TIMER(); } //Turn on the compare unit (ie turn on the interrupt) if boost duty >0
}
else
{
//If boost target is 0, turn everything off
TIMSK1 &= ~(1 << OCIE1A); //Turn off timer
digitalWrite(pinBoost, LOW);
DISABLE_BOOST_TIMER(); //Turn off timer
BOOST_PIN_LOW();
}
}
else
{
//Boost control does nothing if kPa below 100
TIMSK1 &= ~(1 << OCIE1A); //Turn off timer
digitalWrite(pinBoost, LOW); //Make sure solenoid is off (0% duty)
DISABLE_BOOST_TIMER(); //Turn off timer
BOOST_PIN_LOW(); //Make sure solenoid is off (0% duty)
}
}
else { TIMSK1 &= ~(1 << OCIE1A); } // Disable timer channel
else { DISABLE_BOOST_TIMER(); } // Disable timer channel
boostCounter++;
}
@ -106,51 +114,73 @@ void vvtControl()
if( configPage3.vvtEnabled == 1 )
{
byte vvtDuty = get3DTableValue(&vvtTable, currentStatus.TPS, currentStatus.RPM);
vvt_pwm_target_value = percentage(vvtDuty, vvt_pwm_max_count);
if(vvtDuty == 0)
{
//Make sure solenoid is off (0% duty)
VVT_PIN_LOW();
DISABLE_VVT_TIMER();
}
else if (vvtDuty >= 100)
{
//Make sure solenoid is on (100% duty)
VVT_PIN_HIGH();
DISABLE_VVT_TIMER();
}
else
{
vvt_pwm_target_value = percentage(vvtDuty, vvt_pwm_max_count);
ENABLE_VVT_TIMER();
}
}
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
else { TIMSK1 &= ~(1 << OCIE1B); } // Disable timer channel
#endif
else { DISABLE_VVT_TIMER(); } // Disable timer channel
}
//The interrupt to control the Boost PWM
ISR(TIMER1_COMPA_vect)
#if defined(CORE_AVR)
ISR(TIMER1_COMPA_vect)
#elif defined (CORE_TEENSY)
static inline void boostInterrupt() //Most ARM chips can simply call a function
#endif
{
if (boost_pwm_state)
{
*boost_pin_port &= ~(boost_pin_mask); // Switch pin to low
OCR1A = TCNT1 + (boost_pwm_max_count - boost_pwm_cur_value);
BOOST_PIN_LOW(); // Switch pin to low
BOOST_TIMER_COMPARE = BOOST_TIMER_COUNTER + (boost_pwm_max_count - boost_pwm_cur_value);
boost_pwm_state = false;
}
else
{
*boost_pin_port |= (boost_pin_mask); // Switch pin high
OCR1A = TCNT1 + boost_pwm_target_value;
BOOST_PIN_HIGH(); // Switch pin high
BOOST_TIMER_COMPARE = BOOST_TIMER_COUNTER + boost_pwm_target_value;
boost_pwm_cur_value = boost_pwm_target_value;
boost_pwm_state = true;
}
}
//The interrupt to control the VVT PWM
ISR(TIMER1_COMPB_vect)
#if defined(CORE_AVR)
ISR(TIMER1_COMPB_vect)
#elif defined (CORE_TEENSY)
static inline void vvtInterrupt() //Most ARM chips can simply call a function
#endif
{
if (vvt_pwm_state)
{
*vvt_pin_port &= ~(vvt_pin_mask); // Switch pin to low
OCR1B = TCNT1 + (vvt_pwm_max_count - vvt_pwm_cur_value);
VVT_PIN_LOW(); // Switch pin to low
VVT_TIMER_COMPARE = VVT_TIMER_COUNTER + (vvt_pwm_max_count - vvt_pwm_cur_value);
vvt_pwm_state = false;
}
else
{
*vvt_pin_port |= (vvt_pin_mask); // Switch pin high
OCR1B = TCNT1 + vvt_pwm_target_value;
VVT_PIN_HIGH(); // Switch pin high
VVT_TIMER_COMPARE = VVT_TIMER_COUNTER + vvt_pwm_target_value;
vvt_pwm_cur_value = vvt_pwm_target_value;
vvt_pwm_state = true;
}
}
#elif defined (CORE_TEENSY) || defined(CORE_STM32)
//YET TO BE IMPLEMENTED ON TEENSY
#elif defined(CORE_STM32)
//YET TO BE IMPLEMENTED ON STM32
void initialiseAuxPWM() { }
void boostControl() { }
void vvtControl() { }

View File

@ -15,8 +15,8 @@ uint8_t Glow, Ghigh;
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
HardwareSerial &CANSerial = Serial3;
#elif defined(CORE_STM32)
SerialUART &CANSerial = Serial2;
//HardwareSerial &CANSerial = Serial2;
SerialUART &CANSerial = Serial2;
#elif defined(CORE_TEENSY)
HardwareSerial &CANSerial = Serial2;
#endif

View File

@ -18,41 +18,41 @@ void canCommand()
switch (currentcanCommand)
{
case 'A': // sends the bytes of realtime values
sendValues(0, packetSize,3); //send values to serial3
sendValues(0, packetSize,0x30,3); //send values to serial3
break;
case 'G': // this is the reply command sent by the Can interface
//uint8_t Gdata;
while (CANSerial.available() == 0) { }
byte destcaninchannel;
if (CANSerial.available() >= 10)
{
cancmdfail = CANSerial.read();
destcaninchannel = CANSerial.read();
if (cancmdfail != 0)
{
for (byte Gx = 0; Gx < 8; Gx++) //read all 8 bytes of data
{
while (CANSerial.available() == 0) { }
Gdata[Gx] = CANSerial.read();
}
Glow = Gdata[(configPage10.caninput_param_start_byte[currentStatus.current_caninchannel])];
if (configPage10.caninput_param_num_bytes[currentStatus.current_caninchannel] == 2)
{
if ((configPage10.caninput_param_start_byte[currentStatus.current_caninchannel]) != 7) //you cant have a 2 byte value starting at byte 7(8 on the list)
{
Ghigh = Gdata[((configPage10.caninput_param_start_byte[currentStatus.current_caninchannel])+1)];
}
}
{ // read all 8 bytes of data.
for (byte Gx = 0; Gx < 8; Gx++) // first two are the can address the data is from. next two are the can address the data is for.then next 1 or two bytes of data
{
Gdata[Gx] = CANSerial.read();
}
Glow = Gdata[(configPage10.caninput_param_start_byte[destcaninchannel]&7)];
if ((BIT_CHECK(configPage10.caninput_param_num_bytes,destcaninchannel))) //if true then num bytes is 2
{
if ((configPage10.caninput_param_start_byte[destcaninchannel]&7) < 8) //you cant have a 2 byte value starting at byte 7(8 on the list)
{
Ghigh = Gdata[((configPage10.caninput_param_start_byte[destcaninchannel]&7)+1)];
}
else{Ghigh = 0;}
}
else
{
Ghigh = 0;
}
{
Ghigh = 0;
}
currentStatus.canin[currentStatus.current_caninchannel] = word(Ghigh, Glow);
currentStatus.canin[destcaninchannel] = (Ghigh<<8) | Glow;
}
else{} //continue as command request failed and/or data/device was not available
if (currentStatus.current_caninchannel <= 6) // if channel is 0-7
if (currentStatus.current_caninchannel < 15) // if channel is < 15 then we can do another one
{
currentStatus.current_caninchannel++; //inc to next channel
}
@ -60,7 +60,7 @@ void canCommand()
{
currentStatus.current_caninchannel = 0; //reset to start
}
}
break;
case 'L':
@ -86,23 +86,22 @@ void canCommand()
break;
case 'r': //New format for the optimised OutputChannels
byte cmd;
byte Cmd;
if (CANSerial.available() >= 6)
{
CANSerial.read(); //Read the $tsCanId
cmd = CANSerial.read();
Cmd = CANSerial.read();
uint16_t offset, length;
if(cmd == 0x30) //Send output channels command 0x30 is 48dec
if( (Cmd == 0x30) || ( (Cmd >= 0x40) && (Cmd <0x50) ) ) //Send output channels command 0x30 is 48dec, 0x40(64dec)-0x4F(79dec) are external can request
{
byte tmp;
tmp = CANSerial.read();
offset = word(CANSerial.read(), tmp);
tmp = CANSerial.read();
length = word(CANSerial.read(), tmp);
sendValues(offset, length, 3);
sendValues(offset, length,Cmd, 3);
//Serial.print(Cmd);
}
else
{
@ -152,14 +151,16 @@ void sendCancommand(uint8_t cmdtype, uint16_t canaddress, uint8_t candata1, uint
CANSerial.write(canaddress); //11 bit canaddress of device to listen for
break;
case 2:
CANSerial.print("R"); //send "R" to request data from the parmagroup whos value is sent next
CANSerial.write( lowByte(paramgroup) ); //send lsb first
CANSerial.write( lowByte(paramgroup >> 8) );
case 2: // requests via serial3
CANSerial.print("R"); //send "R" to request data from the parmagroup can address whos value is sent next
CANSerial.write(candata1); //the currentStatus.current_caninchannel
CANSerial.write(lowByte(paramgroup) ); //send lsb first
CANSerial.write(highByte(paramgroup) );
break;
case 3:
//send to truecan send routine
//canaddress == speeduino canid, candata1 == canin channel dest, paramgroup == can address to request from
break;
default:

View File

@ -11,8 +11,9 @@
#define boostvvtPage 8
#define seqFuelPage 9
#define canbusPage 10//Config Page 10
#define warmupPage 11 //Config Page 11
#define packetSize 57//41
#define packetSize 73
byte currentPage = 1;//Not the same as the speeduino config page numbers
bool isMap = true;
@ -40,7 +41,7 @@ const char pageTitles[] PROGMEM //This is being stored in the avr flash instead
};
void command();//This is the heart of the Command Line Interpeter. All that needed to be done was to make it human readable.
void sendValues(uint16_t offset, uint16_t packetlength, byte portnum);
void sendValues(uint16_t offset, uint16_t packetlength,byte cmd, byte portnum);
void receiveValue(int offset, byte newValue);
void saveConfig();
void sendPage(bool useChar);

View File

@ -15,15 +15,16 @@ A detailed description of each call can be found at: http://www.msextra.com/doc/
void command()
{
if (cmdPending == 0) { currentCommand = Serial.read(); }
if (!cmdPending) { currentCommand = Serial.read(); }
switch (currentCommand)
{
case 'A': // send x bytes of realtime values
sendValues(0, packetSize, 0); //send values to serial0
sendValues(0, packetSize,0x30, 0); //send values to serial0
break;
case 'B': // Burn current values to eeprom
writeConfig();
break;
@ -79,12 +80,12 @@ void command()
break;
case 'S': // send code version
Serial.print(displaySignature);Serial.print(".");Serial.print(TSfirmwareVersion);
Serial.print("Speeduino 2017.07-dev");
currentStatus.secl = 0; //This is required in TS3 due to its stricter timings
break;
case 'Q': // send code version
Serial.print(displaySignature);Serial.print(TSfirmwareVersion);
Serial.print("speeduino 201707-dev");
break;
case 'V': // send VE table and constants in binary
@ -181,15 +182,15 @@ void command()
tsCanId = Serial.read(); //Read the $tsCanId
cmd = Serial.read(); // read the command
uint16_t valueOffset, length;
uint16_t offset, length;
if(cmd == 0x30) //Send output channels command 0x30 is 48dec
{
byte tmp;
tmp = Serial.read();
valueOffset = word(Serial.read(), tmp);
offset = word(Serial.read(), tmp);
tmp = Serial.read();
length = word(Serial.read(), tmp);
sendValues(valueOffset, length, 0);
sendValues(offset, length,cmd, 0);
}
else
{
@ -243,33 +244,23 @@ void command()
This function returns the current values of a fixed group of variables
*/
//void sendValues(int packetlength, byte portNum)
void sendValues(uint16_t offset, uint16_t packetLength, byte portNum)
void sendValues(uint16_t offset, uint16_t packetLength, byte cmd, byte portNum)
{
byte fullStatus[packetSize];
if (portNum == 3)
{
//CAN serial
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) //ATmega2561 does not have Serial3
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)|| defined(CORE_STM32) || defined (CORE_TEENSY) //ATmega2561 does not have Serial3
if (offset == 0)
{
Serial3.write("A"); //confirm cmd type
CANSerial.write("A"); //confirm cmd type
}
else
{
Serial3.write("r"); //confirm cmd type
CANSerial.write("r"); //confirm cmd type
CANSerial.write(cmd);
}
Serial3.write(packetLength); //confirm no of byte to be sent
#elif defined(CORE_STM32) || defined (CORE_TEENSY)
if (offset == 0)
{
Serial2.write("A"); //confirm cmd type
}
else
{
Serial2.write("r"); //confirm cmd type
}
Serial2.write(packetLength); //confirm no of byte to be sent
#endif
}
else
@ -284,19 +275,19 @@ void sendValues(uint16_t offset, uint16_t packetLength, byte portNum)
fullStatus[1] = currentStatus.squirt; //Squirt Bitfield
fullStatus[2] = currentStatus.engine; //Engine Status Bitfield
fullStatus[3] = (byte)(divu100(currentStatus.dwell)); //Dwell in ms * 10
fullStatus[4] = (byte)(currentStatus.MAP >> 1); //map value is divided by 2
fullStatus[5] = (byte)(currentStatus.IAT + CALIBRATION_TEMPERATURE_OFFSET); //mat
fullStatus[6] = (byte)(currentStatus.coolant + CALIBRATION_TEMPERATURE_OFFSET); //Coolant ADC
fullStatus[7] = currentStatus.tpsADC; //TPS (Raw 0-255)
fullStatus[8] = currentStatus.battery10; //battery voltage
fullStatus[9] = currentStatus.O2; //O2
fullStatus[10] = currentStatus.egoCorrection; //Exhaust gas correction (%)
fullStatus[11] = currentStatus.iatCorrection; //Air temperature Correction (%)
fullStatus[12] = currentStatus.wueCorrection; //Warmup enrichment (%)
fullStatus[13] = lowByte(currentStatus.RPM); //rpm HB
fullStatus[14] = highByte(currentStatus.RPM); //rpm LB
fullStatus[15] = currentStatus.TAEamount; //acceleration enrichment (%)
fullStatus[16] = currentStatus.baro; //Barometer value
fullStatus[4] = lowByte(currentStatus.MAP); //2 bytes for MAP
fullStatus[5] = highByte(currentStatus.MAP);
fullStatus[6] = (byte)(currentStatus.IAT + CALIBRATION_TEMPERATURE_OFFSET); //mat
fullStatus[7] = (byte)(currentStatus.coolant + CALIBRATION_TEMPERATURE_OFFSET); //Coolant ADC
fullStatus[8] = currentStatus.batCorrection; //Battery voltage correction (%)
fullStatus[9] = currentStatus.battery10; //battery voltage
fullStatus[10] = currentStatus.O2; //O2
fullStatus[11] = currentStatus.egoCorrection; //Exhaust gas correction (%)
fullStatus[12] = currentStatus.iatCorrection; //Air temperature Correction (%)
fullStatus[13] = currentStatus.wueCorrection; //Warmup enrichment (%)
fullStatus[14] = lowByte(currentStatus.RPM); //rpm HB
fullStatus[15] = highByte(currentStatus.RPM); //rpm LB
fullStatus[16] = currentStatus.TAEamount; //acceleration enrichment (%)
fullStatus[17] = currentStatus.corrections; //Total GammaE (%)
fullStatus[18] = currentStatus.VE; //Current VE 1 (%)
fullStatus[19] = currentStatus.afrTarget;
@ -313,9 +304,9 @@ void sendValues(uint16_t offset, uint16_t packetLength, byte portNum)
fullStatus[26] = lowByte(currentStatus.freeRAM); //(byte)((currentStatus.loopsPerSecond >> 8) & 0xFF);
fullStatus[27] = highByte(currentStatus.freeRAM);
fullStatus[28] = currentStatus.batCorrection; //Battery voltage correction (%)
fullStatus[29] = currentStatus.spark; //Spark related bitfield
fullStatus[30] = currentStatus.O2_2; //O2
fullStatus[28] = currentStatus.boostTarget;
fullStatus[29] = currentStatus.boostDuty;
fullStatus[30] = currentStatus.spark; //Spark related bitfield
//rpmDOT must be sent as a signed integer
fullStatus[31] = lowByte(currentStatus.rpmDOT);
@ -325,10 +316,13 @@ void sendValues(uint16_t offset, uint16_t packetLength, byte portNum)
fullStatus[34] = currentStatus.flexCorrection; //Flex fuel correction (% above or below 100)
fullStatus[35] = currentStatus.flexIgnCorrection; //Ignition correction (Increased degrees of advance) for flex fuel
fullStatus[36] = getNextError();
fullStatus[37] = currentStatus.boostTarget;
fullStatus[38] = currentStatus.boostDuty;
fullStatus[39] = currentStatus.idleLoad;
fullStatus[40] = currentStatus.testOutputs;
fullStatus[37] = currentStatus.idleLoad;
fullStatus[38] = currentStatus.testOutputs;
fullStatus[39] = currentStatus.O2_2; //O2
fullStatus[40] = currentStatus.baro; //Barometer value
fullStatus[41] = lowByte(currentStatus.canin[0]);
fullStatus[42] = highByte(currentStatus.canin[0]);
fullStatus[43] = lowByte(currentStatus.canin[1]);
@ -345,13 +339,28 @@ void sendValues(uint16_t offset, uint16_t packetLength, byte portNum)
fullStatus[54] = highByte(currentStatus.canin[6]);
fullStatus[55] = lowByte(currentStatus.canin[7]);
fullStatus[56] = highByte(currentStatus.canin[7]);
fullStatus[57] = lowByte(currentStatus.canin[8]);
fullStatus[58] = highByte(currentStatus.canin[8]);
fullStatus[59] = lowByte(currentStatus.canin[9]);
fullStatus[60] = highByte(currentStatus.canin[9]);
fullStatus[61] = lowByte(currentStatus.canin[10]);
fullStatus[62] = highByte(currentStatus.canin[10]);
fullStatus[63] = lowByte(currentStatus.canin[11]);
fullStatus[64] = highByte(currentStatus.canin[11]);
fullStatus[65] = lowByte(currentStatus.canin[12]);
fullStatus[66] = highByte(currentStatus.canin[12]);
fullStatus[67] = lowByte(currentStatus.canin[13]);
fullStatus[68] = highByte(currentStatus.canin[13]);
fullStatus[69] = lowByte(currentStatus.canin[14]);
fullStatus[70] = highByte(currentStatus.canin[14]);
fullStatus[71] = lowByte(currentStatus.canin[15]);
fullStatus[72] = highByte(currentStatus.canin[15]);
Serial.write((byte *)&fullStatus+offset, packetLength);
//for(byte x=0; x<packetLength; x++)
//{
// if (portNum == 0) { Serial.write(fullStatus[offset+x]); }
// else if (portNum == 3) { CANSerial.write(fullStatus[offset+x]); }
//}
for(byte x=0; x<packetLength; x++)
{
if (portNum == 0) { Serial.write(fullStatus[offset+x]); }
else if (portNum == 3){ CANSerial.write(fullStatus[offset+x]); }
}
}
@ -525,6 +534,15 @@ void receiveValue(int valueOffset, byte newValue)
}
break;
case warmupPage: //Idle Air Control settings page (Page 4)
pnt_configPage = &configPage11;
//For some reason, TunerStudio is sending offsets greater than the maximum page size. I'm not sure if it's their bug or mine, but the fix is to only update the config page if the offset is less than the maximum size
if (valueOffset < page_size)
{
*((byte *)pnt_configPage + (byte)valueOffset) = newValue;
}
break;
default:
break;
}
@ -538,22 +556,19 @@ useChar - If true, all values are send as chars, this is for the serial command
*/
void sendPage(bool useChar)
{
void* pnt_configPage;
struct table3D currentTable;
void* pnt_configPage = &configPage1; //Default value is for safety only. Will be changed below if needed.
struct table3D currentTable = fuelTable; //Default value is for safety only. Will be changed below if needed.
byte currentTitleIndex = 0;// This corresponds to the count up to the first char of a string in pageTitles
bool sendComplete = false; //Used to track whether all send operations are complete
switch (currentPage)
{
case veMapPage:
{
currentTitleIndex = 0;
currentTable = fuelTable;
break;
}
case veSetPage:
{
// currentTitleIndex = 27;
if (useChar)
{
@ -585,17 +600,13 @@ void sendPage(bool useChar)
}
else { pnt_configPage = &configPage1; } //Create a pointer to Page 1 in memory
break;
}
case ignMapPage:
{
currentTitleIndex = 42;// the index to the first char of the third string in pageTitles
currentTable = ignitionTable;
break;
}
case ignSetPage:
{
//currentTitleIndex = 56;
if (useChar)
{
@ -642,17 +653,13 @@ void sendPage(bool useChar)
}
else { pnt_configPage = &configPage2; } //Create a pointer to Page 2 in memory
break;
}
case afrMapPage:
{
currentTitleIndex = 71;//Array index to next string
currentTable = afrTable;
break;
}
case afrSetPage:
{
//currentTitleIndex = 91;
if (useChar)
{
@ -697,10 +704,8 @@ void sendPage(bool useChar)
}
else { pnt_configPage = &configPage3; } //Create a pointer to Page 3 in memory
break;
}
case iacPage:
{
//currentTitleIndex = 106;
//To Display Values from Config Page 4
if (useChar)
@ -747,10 +752,8 @@ void sendPage(bool useChar)
}
else { pnt_configPage = &configPage4; } //Create a pointer to Page 4 in memory
break;
}
case boostvvtPage:
{
if(useChar)
{
currentTable = boostTable;
@ -773,9 +776,8 @@ void sendPage(bool useChar)
sendComplete = true;
}
break;
}
case seqFuelPage:
{
if(useChar)
{
currentTable = trim1Table;
@ -836,10 +838,8 @@ void sendPage(bool useChar)
sendComplete = true;
}
break;
}
case canbusPage:
{
//currentTitleIndex = 141;
if (useChar)
{
@ -853,14 +853,22 @@ void sendPage(bool useChar)
}
else { pnt_configPage = &configPage10; } //Create a pointer to Page 10 in memory
break;
}
case warmupPage:
if (useChar)
{
sendComplete = true;
}
else { pnt_configPage = &configPage11; } //Create a pointer to Page 4 in memory
break;
default:
{
Serial.println(F("\nPage has not been implemented yet. Change to another page."));
//Just set default Values to avoid warnings
pnt_configPage = &configPage11;
currentTable = fuelTable;
sendComplete = true;
break;
}
}
if(!sendComplete)
{
@ -1010,13 +1018,18 @@ void receiveCalibration(byte tableID)
break;
default:
OFFSET = 0;
pnt_TargetTable = (byte *)&o2CalibrationTable;
DIVISION_FACTOR = 1;
BYTES_PER_VALUE = 1;
EEPROM_START = EEPROM_CALIBRATION_O2;
break; //Should never get here, but if we do, just fail back to main loop
}
//1024 value pairs are sent. We have to receive them all, but only use every second one (We only store 512 calibratino table entries to save on EEPROM space)
//The values are sent as 2 byte ints, but we convert them to single bytes. Any values over 255 are capped at 255.
int tempValue;
int tempBuffer;
byte tempBuffer[2];
bool every2nd = true;
int x;
int counter = 0;
@ -1034,10 +1047,10 @@ void receiveCalibration(byte tableID)
else
{
while ( Serial.available() < 2 ) {}
tempBuffer = Serial.read();
tempBuffer |= Serial.read() << 8;
tempBuffer[0] = Serial.read();
tempBuffer[1] = Serial.read();
tempValue = div(int(tempBuffer), DIVISION_FACTOR).quot; //Read 2 bytes, convert to word (an unsigned int), convert to signed int. These values come through * 10 from Tuner Studio
tempValue = div(int(word(tempBuffer[1], tempBuffer[0])), DIVISION_FACTOR).quot; //Read 2 bytes, convert to word (an unsigned int), convert to signed int. These values come through * 10 from Tuner Studio
tempValue = ((tempValue - 32) * 5) / 9; //Convert from F to C
}
tempValue = tempValue + OFFSET;

View File

@ -112,7 +112,11 @@ Additional fuel % to be added when the engine is cranking
static inline byte correctionCranking()
{
byte crankingValue = 100;
if ( BIT_CHECK(currentStatus.engine, BIT_ENGINE_CRANK) ) { crankingValue = 100 + configPage1.crankingPct; }
//if ( BIT_CHECK(currentStatus.engine, BIT_ENGINE_CRANK) ) { crankingValue = 100 + configPage1.crankingPct; }
if ( BIT_CHECK(currentStatus.engine, BIT_ENGINE_CRANK) )
{
crankingValue = table2D_getValue(&crankingEnrichTable, currentStatus.coolant + CALIBRATION_TEMPERATURE_OFFSET);
}
return crankingValue;
}
@ -152,12 +156,13 @@ static inline byte correctionAccel()
if( BIT_CHECK(currentStatus.engine, BIT_ENGINE_ACC) )
{
//If it is currently running, check whether it should still be running or whether it's reached it's end time
if( currentLoopTime >= currentStatus.TAEEndTime )
if( micros() >= currentStatus.TAEEndTime )
{
//Time to turn enrichment off
BIT_CLEAR(currentStatus.engine, BIT_ENGINE_ACC);
currentStatus.TAEamount = 0;
accelValue = 100;
currentStatus.tpsDOT = 0;
}
else
{
@ -167,15 +172,18 @@ static inline byte correctionAccel()
}
else
{
int8_t TPS_change = (currentStatus.TPS - currentStatus.TPSlast);
//Check for deceleration (Deceleration adjustment not yet supported)
if (currentStatus.TPS < currentStatus.TPSlast)
//Also check for only very small movement (Movement less than or equal to 2% is ignored). This not only means we can skip the lookup, but helps reduce false triggering around 0-2% throttle openings
if (TPS_change <= 2)
{
accelValue = 100;
currentStatus.tpsDOT = 0;
}
else
{
//If TAE isn't currently turned on, need to check whether it needs to be turned on
int rateOfChange = ldiv(1000000, (currentStatus.TPS_time - currentStatus.TPSlast_time)).quot * (currentStatus.TPS - currentStatus.TPSlast); //This is the % per second that the TPS has moved
int rateOfChange = ldiv(1000000, (currentStatus.TPS_time - currentStatus.TPSlast_time)).quot * TPS_change; //This is the % per second that the TPS has moved
currentStatus.tpsDOT = rateOfChange / 10; //The TAE bins are divided by 10 in order to allow them to be stored in a byte. Faster as this than divu10
if (rateOfChange > configPage1.tpsThresh)

View File

@ -15,6 +15,8 @@ static inline void addToothLogEntry(unsigned long);
static inline uint16_t stdGetRPM();
static inline void setFilter(unsigned long);
static inline int crankingGetRPM(byte);
static inline void doPerToothTiming(uint16_t crankAngle);
void triggerSetup_missingTooth();
void triggerPri_missingTooth();
void triggerSec_missingTooth();
@ -61,6 +63,11 @@ bool secondDerivEnabled; //The use of the 2nd derivative calculation is limited
bool decoderIsSequential; //Whether or not the decoder supports sequential operation
byte checkSyncToothCount; //How many teeth must've been seen on this revolution before we try to confirm sync (Useful for missing tooth type decoders)
int16_t ignition1EndTooth = 0;
int16_t ignition2EndTooth = 0;
int16_t ignition3EndTooth = 0;
int16_t ignition4EndTooth = 0;
int toothAngles[24]; //An array for storing fixed tooth angles. Currently sized at 24 for the GM 24X decoder, but may grow later if there are other decoders that use this style
//Used for identifying long and short pulses on the 4G63 (And possibly other) trigger patterns

View File

@ -94,11 +94,24 @@ static inline int crankingGetRPM(byte totalTeeth)
revolutionTime = (toothLastToothTime - toothLastMinusOneToothTime) * totalTeeth;
interrupts();
tempRPM = (US_IN_MINUTE / revolutionTime);
if(tempRPM >= MAX_RPM) { tempRPM = currentStatus.RPM; } //Sanity check
if( tempRPM >= MAX_RPM ) { tempRPM = currentStatus.RPM; } //Sanity check. This can prevent spiking caused by noise on individual teeth. The new RPM should never be above 4x the cranking setting value (Remembering that this function is only called is the current RPM is less than the cranking setting)
}
return tempRPM;
}
/*
On decoders that are enabled for per tooth based timing adjustments, this function performs the timer compare changes on the schedules themselves
For each ignition channel, a check is made whether we're at the relevant tooth and whether that ignition schedule is currently running
Only if both these conditions are met will the schedule be updated with the latest timing information.
*/
static inline void doPerToothTiming(uint16_t crankAngle)
{
if ( (toothCurrentCount == ignition1EndTooth) && (ignitionSchedule1.Status == RUNNING) ) { IGN1_COMPARE = IGN1_COUNTER + uS_TO_TIMER_COMPARE( (ignition1EndAngle - crankAngle) * timePerDegree ); }
else if ( (toothCurrentCount == ignition2EndTooth) && (ignitionSchedule2.Status == RUNNING) ) { IGN2_COMPARE = IGN2_COUNTER + uS_TO_TIMER_COMPARE( (ignition2EndAngle - crankAngle) * timePerDegree ); }
else if ( (toothCurrentCount == ignition3EndTooth) && (ignitionSchedule3.Status == RUNNING) ) { IGN3_COMPARE = IGN3_COUNTER + uS_TO_TIMER_COMPARE( (ignition3EndAngle - crankAngle) * timePerDegree ); }
else if ( (toothCurrentCount == ignition4EndTooth) && (ignitionSchedule4.Status == RUNNING) ) { IGN4_COMPARE = IGN4_COUNTER + uS_TO_TIMER_COMPARE( (ignition4EndAngle - crankAngle) * timePerDegree ); }
}
/*
Name: Missing tooth wheel
Desc: A multi-tooth wheel with one of more 'missing' teeth. The first tooth after the missing one is considered number 1 and isthe basis for the trigger angle
@ -161,7 +174,12 @@ void triggerPri_missingTooth()
}
}
//EXPERIMENTAL!
if(configPage1.perToothIgn == true)
{
uint16_t crankAngle = ( (toothCurrentCount-1) * triggerToothAngle ) + configPage2.triggerAngle;
doPerToothTiming(crankAngle);
}
}
}
@ -174,7 +192,7 @@ void triggerSec_missingTooth()
uint16_t getRPM_missingTooth()
{
uint16_t tempRPM = 0;
if( currentStatus.RPM < (unsigned int)(configPage2.crankRPM * 100) )
if( (currentStatus.RPM < (unsigned int)(configPage2.crankRPM * 100)) && (toothCurrentCount != 1) ) //Can't do per tooth RPM if we're at tooth #1 as the missing tooth messes the calculation
{
if(configPage2.TrigSpeed == 1) { crankingGetRPM(configPage2.triggerTeeth/2); } //Account for cam speed
else { tempRPM = crankingGetRPM(configPage2.triggerTeeth); }
@ -217,6 +235,32 @@ int getCrankAngle_missingTooth(int timePerDegree)
return crankAngle;
}
void triggerSetEndTeeth_missingTooth()
{
ignition1EndTooth = ( (ignition1EndAngle - configPage2.triggerAngle) / triggerToothAngle ) - 1;
if(ignition1EndTooth > configPage2.triggerTeeth) { ignition1EndTooth -= configPage2.triggerTeeth; }
if(ignition1EndTooth <= 0) { ignition1EndTooth -= configPage2.triggerTeeth; }
if(ignition1EndTooth > triggerActualTeeth) { ignition1EndTooth = triggerActualTeeth; }
ignition2EndTooth = ( (ignition2EndAngle - configPage2.triggerAngle) / triggerToothAngle ) - 1;
if(ignition2EndTooth > configPage2.triggerTeeth) { ignition2EndTooth -= configPage2.triggerTeeth; }
if(ignition2EndTooth <= 0) { ignition2EndTooth -= configPage2.triggerTeeth; }
if(ignition2EndTooth > triggerActualTeeth) { ignition2EndTooth = triggerActualTeeth; }
ignition3EndTooth = ( (ignition3EndAngle - configPage2.triggerAngle) / triggerToothAngle ) - 1;
if(ignition3EndTooth > configPage2.triggerTeeth) { ignition3EndTooth -= configPage2.triggerTeeth; }
if(ignition3EndTooth <= 0) { ignition3EndTooth -= configPage2.triggerTeeth; }
if(ignition3EndTooth > triggerActualTeeth) { ignition3EndTooth = triggerActualTeeth; }
ignition4EndTooth = ( (ignition4EndAngle - configPage2.triggerAngle) / triggerToothAngle ) - 1;
if(ignition4EndTooth > configPage2.triggerTeeth) { ignition4EndTooth -= configPage2.triggerTeeth; }
if(ignition4EndTooth <= 0) { ignition4EndTooth -= configPage2.triggerTeeth; }
if(ignition4EndTooth > triggerActualTeeth) { ignition4EndTooth = triggerActualTeeth; }
}
/* -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
Name: Dual wheel
Desc: 2 wheels located either both on the crank or with the primary on the crank and the secondary on the cam.
@ -225,6 +269,7 @@ Note: There can be no missing teeth on the primary wheel
void triggerSetup_DualWheel()
{
triggerToothAngle = 360 / configPage2.triggerTeeth; //The number of degrees that passes from tooth to tooth
if(configPage2.TrigSpeed == 1) { triggerToothAngle = 720 / configPage2.triggerTeeth; } //Account for cam speed missing tooth
toothCurrentCount = 255; //Default value
triggerFilterTime = (int)(1000000 / (MAX_RPM / 60 * configPage2.triggerTeeth)); //Trigger filter time is the shortest possible time (in uS) that there can be between crank teeth (ie at max RPM). Any pulses that occur faster than this time will be disgarded as noise
triggerSecFilterTime = (int)(1000000 / (MAX_RPM / 60 * 2)) / 2; //Same as above, but fixed at 2 teeth on the secondary input and divided by 2 (for cam speed)
@ -259,6 +304,13 @@ void triggerPri_DualWheel()
setFilter(curGap); //Recalc the new filter value
}
//EXPERIMENTAL!
if(configPage1.perToothIgn == true)
{
uint16_t crankAngle = ( (toothCurrentCount-1) * triggerToothAngle ) + configPage2.triggerAngle;
doPerToothTiming(crankAngle);
}
} //TRigger filter
@ -330,6 +382,29 @@ int getCrankAngle_DualWheel(int timePerDegree)
return crankAngle;
}
void triggerSetEndTeeth_DualWheel()
{
ignition1EndTooth = ( (ignition1EndAngle - configPage2.triggerAngle) / triggerToothAngle ) - 1;
if(ignition1EndTooth > configPage2.triggerTeeth) { ignition1EndTooth -= configPage2.triggerTeeth; }
if(ignition1EndTooth <= 0) { ignition1EndTooth -= configPage2.triggerTeeth; }
if(ignition1EndTooth > triggerActualTeeth) { ignition1EndTooth = triggerActualTeeth; }
ignition2EndTooth = ( (ignition2EndAngle - configPage2.triggerAngle) / triggerToothAngle ) - 1;
if(ignition2EndTooth > configPage2.triggerTeeth) { ignition2EndTooth -= configPage2.triggerTeeth; }
if(ignition2EndTooth <= 0) { ignition2EndTooth -= configPage2.triggerTeeth; }
if(ignition2EndTooth > triggerActualTeeth) { ignition2EndTooth = triggerActualTeeth; }
ignition3EndTooth = ( (ignition3EndAngle - configPage2.triggerAngle) / triggerToothAngle ) - 1;
if(ignition3EndTooth > configPage2.triggerTeeth) { ignition3EndTooth -= configPage2.triggerTeeth; }
if(ignition3EndTooth <= 0) { ignition3EndTooth -= configPage2.triggerTeeth; }
if(ignition3EndTooth > triggerActualTeeth) { ignition3EndTooth = triggerActualTeeth; }
ignition4EndTooth = ( (ignition4EndAngle - configPage2.triggerAngle) / triggerToothAngle ) - 1;
if(ignition4EndTooth > configPage2.triggerTeeth) { ignition4EndTooth -= configPage2.triggerTeeth; }
if(ignition4EndTooth <= 0) { ignition4EndTooth -= configPage2.triggerTeeth; }
if(ignition4EndTooth > triggerActualTeeth) { ignition4EndTooth = triggerActualTeeth; }
}
/* -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
Name: Basic Distributor
@ -343,8 +418,10 @@ void triggerSetup_BasicDistributor()
triggerToothAngle = 720 / triggerActualTeeth; //The number of degrees that passes from tooth to tooth
triggerFilterTime = 60000000L / MAX_RPM / configPage1.nCylinders; // Minimum time required between teeth
triggerFilterTime = triggerFilterTime / 2; //Safety margin
triggerFilterTime = 0;
secondDerivEnabled = false;
decoderIsSequential = false;
toothCurrentCount = 0; //Default value
if(configPage1.nCylinders <= 4) { MAX_STALL_TIME = (1851UL * triggerToothAngle); }//Minimum 90rpm. (1851uS is the time per degree at 90rpm). This uses 90rpm rather than 50rpm due to the potentially very high stall time on a 4 cylinder if we wait that long.
else { MAX_STALL_TIME = (3200UL * triggerToothAngle); } //Minimum 50rpm. (3200uS is the time per degree at 50rpm).
@ -355,7 +432,7 @@ void triggerPri_BasicDistributor()
{
curTime = micros();
curGap = curTime - toothLastToothTime;
if ( curGap >= triggerFilterTime )
if ( (curGap >= triggerFilterTime) )
{
if( (toothCurrentCount == triggerActualTeeth) || (currentStatus.hasSync == false) ) //Check if we're back to the beginning of a revolution
{
@ -381,6 +458,20 @@ void triggerPri_BasicDistributor()
endCoil4Charge();
}
if(configPage1.perToothIgn == true)
{
uint16_t crankAngle = ( (toothCurrentCount-1) * triggerToothAngle ) + configPage2.triggerAngle;
if ( (toothCurrentCount == ignition1EndTooth) && (ignitionSchedule1.Status == RUNNING) )
{
IGN1_COMPARE = IGN1_COUNTER + uS_TO_TIMER_COMPARE( (ignition1EndAngle - crankAngle) * timePerDegree );
//IGN1_COMPARE = IGN1_COUNTER + uS_TO_TIMER_COMPARE( (ignition1EndAngle - crankAngle)*my_timePerDegree - micros_compensation );
}
else if ( (toothCurrentCount == ignition2EndTooth) && (ignitionSchedule2.Status == RUNNING) ) { IGN2_COMPARE = IGN2_COUNTER + uS_TO_TIMER_COMPARE( (ignition2EndAngle - crankAngle) * timePerDegree ); }
else if ( (toothCurrentCount == ignition3EndTooth) && (ignitionSchedule3.Status == RUNNING) ) { IGN3_COMPARE = IGN3_COUNTER + uS_TO_TIMER_COMPARE( (ignition3EndAngle - crankAngle) * timePerDegree ); }
else if ( (toothCurrentCount == ignition4EndTooth) && (ignitionSchedule4.Status == RUNNING) ) { IGN4_COMPARE = IGN4_COUNTER + uS_TO_TIMER_COMPARE( (ignition4EndAngle - crankAngle) * timePerDegree ); }
}
toothLastMinusOneToothTime = toothLastToothTime;
toothLastToothTime = curTime;
} //Trigger filter
@ -392,7 +483,10 @@ uint16_t getRPM_BasicDistributor()
if( currentStatus.RPM < (unsigned int)(configPage2.crankRPM * 100) )
{ tempRPM = crankingGetRPM(triggerActualTeeth >> 1); } //crankGetRPM uses teeth per 360 degrees. As triggerActualTeeh is total teeth in 720 degrees, we divide the tooth count by 2
else
{ tempRPM = stdGetRPM() << 1; } //Multiply RPM by 2 due to tracking over 720 degrees now rather than 360
{
tempRPM = stdGetRPM() << 1;
revolutionTime = revolutionTime >> 1; //Revolution time has to be divided by 2 as otherwise it would be over 720 degrees (triggerActualTeeth = nCylinders)
} //Multiply RPM by 2 due to tracking over 720 degrees now rather than 360
return tempRPM;
@ -421,6 +515,14 @@ int getCrankAngle_BasicDistributor(int timePerDegree)
return crankAngle;
}
void triggerSetEndTeeth_BasicDistributor()
{
ignition1EndTooth = ( (ignition1EndAngle - configPage2.triggerAngle) / triggerToothAngle ) - 1;
if(ignition1EndTooth > configPage2.triggerTeeth) { ignition1EndTooth -= configPage2.triggerTeeth; }
if(ignition1EndTooth <= 0) { ignition1EndTooth -= configPage2.triggerTeeth; }
if(ignition1EndTooth > triggerActualTeeth) { ignition1EndTooth = triggerActualTeeth; }
}
/* -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
Name: GM7X
Desc: GM 7X trigger wheel. It has six equally spaced teeth and a seventh tooth for cylinder identification.
@ -512,6 +614,11 @@ int getCrankAngle_GM7X(int timePerDegree)
return crankAngle;
}
void triggerSetEndTeeth_GM7X()
{
}
/* -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
Name: Mitsubishi 4G63 / NA/NB Miata + MX-5 / 4/2
@ -574,7 +681,7 @@ void triggerPri_4G63()
{
curTime = micros();
curGap = curTime - toothLastToothTime;
if ( curGap >= triggerFilterTime )
if ( (curGap >= triggerFilterTime) || (currentStatus.startRevolutions == 0) )
{
addToothLogEntry(curGap);
triggerFilterTime = curGap >> 2; //This only applies during non-sync conditions. If there is sync then triggerFilterTime gets changed again below with a better value.
@ -657,7 +764,7 @@ void triggerSec_4G63()
curTime2 = micros();
curGap2 = curTime2 - toothLastSecToothTime;
if ( curGap2 >= triggerSecFilterTime )
if ( (curGap2 >= triggerSecFilterTime) || (currentStatus.startRevolutions == 0) )
{
toothLastSecToothTime = curTime2;
@ -746,6 +853,11 @@ int getCrankAngle_4G63(int timePerDegree)
return crankAngle;
}
void triggerSetEndTeeth_4G63()
{
}
/* -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
Name: GM
Desc: TBA
@ -851,6 +963,11 @@ int getCrankAngle_24X(int timePerDegree)
return crankAngle;
}
void triggerSetEndTeeth_24X()
{
}
/* -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
Name: Jeep 2000
Desc: For '91 to 2000 6 cylinder Jeep engines
@ -947,7 +1064,12 @@ int getCrankAngle_Jeep2000(int timePerDegree)
return crankAngle;
}
/*
void triggerSetEndTeeth_Jeep2000()
{
}
/* -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
Name: Audi 135
Desc: 135 teeth on the crank and 1 tooth on the cam.
Note: This is very similar to the dual wheel decoder, however due to the 135 teeth not dividing evenly into 360, only every 3rd crank tooth is used in calculating the crank angle. This effectively makes it a 45 tooth dual wheel setup
@ -1059,6 +1181,11 @@ int getCrankAngle_Audi135(int timePerDegree)
return crankAngle;
}
void triggerSetEndTeeth_Audi135()
{
}
/* -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
Name: Honda D17
Desc:
@ -1152,6 +1279,11 @@ int getCrankAngle_HondaD17(int timePerDegree)
return crankAngle;
}
void triggerSetEndTeeth_HondaD17()
{
}
/* -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
Name: Miata '99 to '05
Desc: TBA (See: http://forum.diyefi.org/viewtopic.php?f=56&t=1077)
@ -1233,7 +1365,6 @@ void triggerSec_Miata9905()
}
}
uint16_t getRPM_Miata9905()
{
//During cranking, RPM is calculated 4 times per revolution, once for each tooth on the crank signal.
@ -1283,6 +1414,11 @@ int getCrankAngle_Miata9905(int timePerDegree)
return crankAngle;
}
void triggerSetEndTeeth_Miata9905()
{
}
/* -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
Name: Mazda AU version
Desc:
@ -1431,6 +1567,11 @@ int getCrankAngle_MazdaAU(int timePerDegree)
return crankAngle;
}
void triggerSetEndTeeth_MazdaAU()
{
}
/*
Name: Non-360 Dual wheel
Desc: 2 wheels located either both on the crank or with the primary on the crank and the secondary on the cam.
@ -1499,6 +1640,11 @@ int getCrankAngle_non360(int timePerDegree)
return crankAngle;
}
void triggerSetEndTeeth_Non360()
{
}
/* -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
Name: Nissan 360 tooth with cam
Desc:
@ -1666,8 +1812,13 @@ int getCrankAngle_Nissan360(int timePerDegree)
return crankAngle;
}
void triggerSetEndTeeth_Nissan360()
{
}
/* -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
Name: Nissan 360 tooth with cam
Name: Subary 6/7
Desc:
Note:
*/
@ -1810,6 +1961,11 @@ int getCrankAngle_Subaru67(int timePerDegree)
return crankAngle;
}
void triggerSetEndTeeth_Subaru67()
{
}
/* -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
Name: Daihatsu +1 trigger for 3 and 4 cylinder engines
Desc: Tooth equal to the number of cylinders are evenly spaced on the cam. No position sensing (Distributor is retained) so crank angle is a made up figure based purely on the first teeth to be seen
@ -1966,3 +2122,8 @@ int getCrankAngle_Daihatsu(int timePerDegree)
return crankAngle;
}
void triggerSetEndTeeth_Daihatsu()
{
}

View File

@ -18,11 +18,16 @@
#define BOARD_NR_GPIO_PINS 78
#define LED_BUILTIN PA7
#endif
extern "C" char* sbrk(int incr); //Used to freeRam
inline unsigned char digitalPinToInterrupt(unsigned char Interrupt_pin) { return Interrupt_pin; } //This isn't included in the stm32duino libs (yet)
#define portOutputRegister(port) (volatile byte *)( &(port->ODR) )
#define portInputRegister(port) (volatile byte *)( &(port->IDR) )
#if defined(ARDUINO_ARCH_STM32)
#define portOutputRegister(port) (volatile byte *)( &(port->ODR) )
#define portInputRegister(port) (volatile byte *)( &(port->IDR) )
#else
#define portOutputRegister(port) (volatile byte *)( &(port->regs->ODR) ) //These are defined in STM32F1/variants/generic_stm32f103c/variant.h but return a non byte* value
#define portInputRegister(port) (volatile byte *)( &(port->regs->IDR) ) //These are defined in STM32F1/variants/generic_stm32f103c/variant.h but return a non byte* value
#endif
#else
#error Incorrect board selected. Please select the correct board (Usually Mega 2560) and upload again
#endif
@ -74,6 +79,12 @@
#define BIT_SPARK2_UNUSED7 6
#define BIT_SPARK2_UNUSED8 7
#define BIT_TIMER_1HZ 0
#define BIT_TIMER_4HZ 1
#define BIT_TIMER_10HZ 2
#define BIT_TIMER_15HZ 3
#define BIT_TIMER_30HZ 4
#define VALID_MAP_MAX 1022 //The largest ADC value that is valid for the MAP sensor
#define VALID_MAP_MIN 2 //The smallest ADC value that is valid for the MAP sensor
@ -106,16 +117,19 @@
#define SERIAL_BUFFER_THRESHOLD 32 // When the serial buffer is filled to greater than this threshold value, the serial processing operations will be performed more urgently in order to avoid it overflowing. Serial buffer is 64 bytes long, so the threshold is set at half this as a reasonable figure
#define FUEL_PUMP_ON() *pump_pin_port |= (pump_pin_mask)
#define FUEL_PUMP_OFF() *tach_pin_port &= ~(tach_pin_mask)
const byte signature = 20;
//const char signature[] = "speeduino";
const char displaySignature[] = "Speeduino 2017";
const char TSfirmwareVersion[] = "07-dev";
const char displaySignature[] = "speeduino 201609-dev";
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 byte page10_size = 128;
const int npage_size[12] = {0,288,64,288,64,288,64,64,160,192,128,192};
//const byte page11_size = 128;
#define MAP_PAGE_SIZE 288
struct table3D fuelTable; //16x16 fuel map
@ -129,6 +143,7 @@ struct table3D trim3Table; //6x6 Fuel trim 3 map
struct table3D trim4Table; //6x6 Fuel trim 4 map
struct table2D taeTable; //4 bin TPS Acceleration Enrichment map (2D)
struct table2D WUETable; //10 bin Warm Up Enrichment map (2D)
struct table2D crankingEnrichTable; //4 bin cranking Enrichment map (2D)
struct table2D dwellVCorrectionTable; //6 bin dwell voltage correction (2D)
struct table2D injectorVCorrectionTable; //6 bin injector voltage correction (2D)
struct table2D IATDensityCorrectionTable; //9 bin inlet air temperature density correction (2D)
@ -159,6 +174,8 @@ volatile byte ign5_pin_mask;
volatile byte *tach_pin_port;
volatile byte tach_pin_mask;
volatile byte *pump_pin_port;
volatile byte pump_pin_mask;
volatile byte *triggerPri_pin_port;
volatile byte triggerPri_pin_mask;
@ -172,9 +189,17 @@ bool channel3InjEnabled = false;
bool channel4InjEnabled = false;
bool channel5InjEnabled = false;
int ignition1EndAngle = 0;
int ignition2EndAngle = 0;
int ignition3EndAngle = 0;
int ignition4EndAngle = 0;
//This is used across multiple files
unsigned long revolutionTime; //The time in uS that one revolution would take at current speed (The time tooth 1 was last seen, minus the time it was seen prior to that)
volatile byte TIMER_mask;
volatile byte LOOP_TIMER;
//The status struct contains the current values for all 'live' variables
//In current version this is 64 bytes
struct statuses {
@ -182,8 +207,9 @@ struct statuses {
uint16_t RPM;
long longRPM;
int mapADC;
int baroADC;
long MAP; //Has to be a long for PID calcs (Boost control)
byte baro; //Barometric pressure is simply the inital MAP reading, taken before the engine is running
byte baro; //Barometric pressure is simply the inital MAP reading, taken before the engine is running. Alternatively, can be taken from an external sensor
byte TPS; //The current TPS reading (0% - 100%)
byte TPSlast; //The previous TPS reading
unsigned long TPS_time; //The time the TPS sample was taken
@ -232,7 +258,7 @@ struct statuses {
volatile unsigned int loopsPerSecond;
boolean launchingSoft; //True when in launch control soft limit mode
boolean launchingHard; //True when in launch control hard limit mode
unsigned int freeRAM;
uint16_t freeRAM;
unsigned int clutchEngagedRPM;
bool flatShiftingHard;
volatile byte startRevolutions; //A counter for how many revolutions have been completed since sync was achieved.
@ -241,7 +267,7 @@ struct statuses {
bool testActive;
byte boostDuty;
byte idleLoad; //Either the current steps or current duty cycle for the idle control.
int canin[9]; //16bit raw value of selected canin data for channel 1-8
uint16_t canin[16]; //16bit raw value of selected canin data for channel 0-15
uint8_t current_caninchannel = 0; //start off at channel 0
//Helpful bitwise operations:
@ -314,7 +340,7 @@ struct config1 {
byte algorithm : 1; //"Speed Density", "Alpha-N"
byte baroCorr : 1;
byte injLayout : 2;
byte unused2_38g : 1;
byte perToothIgn : 1;
byte unused2_38h : 1;
byte primePulse;
@ -325,7 +351,7 @@ struct config1 {
byte boostMaxDuty;
byte tpsMin;
byte tpsMax;
byte mapMin;
int8_t mapMin; //Must be signed
uint16_t mapMax;
byte fpPrime; //Time (In seconds) that the fuel pump should be primed for on power up
byte stoich;
@ -433,7 +459,8 @@ struct config3 {
byte egoRPM; //RPM must be above this for closed loop to function
byte egoTPSMax; //TPS must be below this for closed loop to function
byte vvtPin : 6;
byte unused6_13 : 2;
byte useExtBaro : 1;
byte unused6_13f : 1;
byte boostPin : 6;
byte unused6_14 : 2;
byte voltageCorrectionBins[6]; //X axis bins for voltage correction tables
@ -466,7 +493,7 @@ struct config3 {
byte lnchPullRes : 2;
byte fuelTrimEnabled : 1;
byte flatSEnable : 1;
byte unused60 : 4;
byte baroPin : 4;
byte flatSSoftWin;
byte flatSRetard;
byte flatSArm;
@ -517,45 +544,18 @@ struct config4 {
struct config10 {
byte enable_canbus:2;
byte enable_candata_in:1;
byte caninput_sel[8];
uint16_t caninput_param_group[8];
uint8_t caninput_param_start_byte[8];
byte caninput_param_num_bytes[8];
byte unused10_41;
byte unused10_42;
byte unused10_43;
byte unused10_44;
byte unused10_45;
byte unused10_46;
byte unused10_47;
byte unused10_48;
byte unused10_49;
uint16_t caninput_sel; //bit status on/off if input is enabled
uint16_t caninput_param_group[16]; //u16 [15] array holding can address of input
uint8_t caninput_param_start_byte[16]; //u08 [15] array holds the start byte number(value of 0-7)
uint16_t caninput_param_num_bytes; //u16 bit status of the number of bytes length 1 or 2
byte unused10_53;
byte unused10_54;
byte enable_candata_out : 1;
byte canoutput_sel[8];
uint16_t canoutput_param_group[8];
uint8_t canoutput_param_start_byte[8];
byte canoutput_param_num_bytes[8];
byte unused10_76;
byte unused10_77;
byte unused10_78;
byte unused10_79;
byte unused10_80;
byte unused10_81;
byte unused10_82;
byte unused10_83;
byte unused10_84;
byte unused10_85;
byte unused10_86;
byte unused10_87;
byte unused10_88;
byte unused10_89;
byte unused10_90;
byte unused10_91;
byte unused10_92;
byte unused10_93;
byte unused10_94;
byte unused10_95;
byte unused10_96;
byte unused10_97;
byte unused10_98;
byte unused10_99;
@ -590,6 +590,64 @@ struct config10 {
} __attribute__((__packed__)); //The 32 bit systems require all structs to be fully packed
#endif
/*
Page 11 - No specific purpose. Created initially for the cranking enrich curve
192 bytes long
See ini file for further info (Config Page 11 in the ini)
*/
struct config11 {
byte crankingEnrichBins[4];
byte crankingEnrichValues[4];
byte unused11_8;
byte unused11_9;
byte unused11_10;
byte unused11_11;
byte unused11_12;
byte unused11_13;
byte unused11_14;
byte unused11_15;
byte unused11_16;
byte unused11_17;
byte unused11_18;
byte unused11_19;
byte unused11_20;
byte unused10_21;
byte unused11_22;
byte unused11_23;
byte unused11_24;
byte unused11_25;
byte unused11_26;
byte unused11_27;
byte unused11_28;
byte unused11_29;
byte unused11_107;
byte unused11_108;
byte unused11_109;
byte unused11_110;
byte unused11_111;
byte unused11_112;
byte unused11_113;
byte unused11_114;
byte unused11_115;
byte unused11_116;
byte unused11_117;
byte unused11_118;
byte unused11_119;
byte unused11_120;
byte unused11_121;
byte unused11_122;
byte unused11_123;
byte unused11_124;
byte unused11_125;
byte unused11_126;
byte unused11_127;
byte unused11_128_192[64];
#if defined(CORE_AVR)
};
#else
} __attribute__((__packed__)); //The 32 bit systems require all structs to be fully packed
#endif
byte pinInjector1; //Output pin injector 1
byte pinInjector2; //Output pin injector 2
@ -648,6 +706,7 @@ byte pinStepperEnable; //Turning the DRV8825 driver on/off
byte pinLaunch;
byte pinIgnBypass; //The pin used for an ignition bypass (Optional)
byte pinFlex; //Pin with the flex sensor attached
byte pinBaro; //Pin that an external barometric pressure sensor is attached to (If used)
// global variables // from speeduino.ino
extern struct statuses currentStatus; // from speeduino.ino
@ -656,10 +715,12 @@ extern struct table3D ignitionTable; //16x16 ignition map
extern struct table3D afrTable; //16x16 afr target map
extern struct table2D taeTable; //4 bin TPS Acceleration Enrichment map (2D)
extern struct table2D WUETable; //10 bin Warm Up Enrichment map (2D)
extern struct table2D crankingEnrichTable; //4 bin cranking Enrichment map (2D)
extern struct config1 configPage1;
extern struct config2 configPage2;
extern struct config3 configPage3;
extern struct config10 configPage10;
extern struct config11 configPage11;
extern unsigned long currentLoopTime; //The time the current loop started (uS)
extern unsigned long previousLoopTime; //The time the previous loop started (uS)
extern byte ignitionCount;

View File

@ -1,7 +1,7 @@
#ifndef MATH_H
#define MATH_H
int fastResize(int, int);
int fastMap1023toX(int, int);
unsigned long percentage(byte, unsigned long);
#endif
#endif

View File

@ -18,11 +18,10 @@ int fastMap(unsigned long x, int in_min, int in_max, int out_min, int out_max)
//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)
//int fastMap1023toX(unsigned long x, int in_min, int in_max, int out_min, int out_max)
//removed ununsed variables, in_min and out_min is aways 0, in_max is aways 1023
#if defined(CORE_STM32)
#define fastResize(x, out_max) ( ((unsigned long)x * out_max) >> 12)
#else
#define fastResize(x, out_max) ( ((unsigned long)x * out_max) >> 10)
#endif
#define fastMap1023toX(x, out_max) ( ((unsigned long)x * out_max) >> 10)
//This is a new version that allows for out_min
#define fastMap10Bit(x, out_min, out_max) ( ( ((unsigned long)x * (out_max-out_min)) >> 10 ) + out_min)
/*
The following are all fast versions of specific divisions
Ref: http://www.hackersdelight.org/divcMore.pdf
@ -74,17 +73,14 @@ int divs100(long n)
//Unsigned divide by 100
unsigned long divu100(unsigned long n)
{
#if defined(CORE_STM32)
return (n / 100); // No difference with this on/off
#else
unsigned long q, r;
q = (n >> 1) + (n >> 3) + (n >> 6) - (n >> 10) +
(n >> 12) + (n >> 13) - (n >> 16);
q = q + (q >> 20);
q = q >> 6;
r = n - q*100;
return q + ((r + 28) >> 7);
#endif
//return (n / 100);
unsigned long q, r;
q = (n >> 1) + (n >> 3) + (n >> 6) - (n >> 10) +
(n >> 12) + (n >> 13) - (n >> 16);
q = q + (q >> 20);
q = q >> 6;
r = n - (q * 100);
return q + ((r + 28) >> 7);
}
//Return x percent of y
@ -104,4 +100,4 @@ inline long powint(int factor, unsigned int exponent)
unsigned int counter = exponent;
while ( (counter--) > 0) { product *= factor; }
return product;
}
}

View File

@ -26,7 +26,7 @@ See page 136 of the processors datasheet: http://www.atmel.com/Images/doc2549.pd
#define SCHEDULER_H
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) || defined(__AVR_ATmega2561__)
#if defined(CORE_AVR)
#include <avr/interrupt.h>
#include <avr/io.h>
@ -35,6 +35,7 @@ See page 136 of the processors datasheet: http://www.atmel.com/Images/doc2549.pd
#define FUEL2_COUNTER TCNT3
#define FUEL3_COUNTER TCNT3
#define FUEL4_COUNTER TCNT4
#define FUEL5_COUNTER TCNT3
#define IGN1_COUNTER TCNT5
#define IGN2_COUNTER TCNT5
@ -46,6 +47,7 @@ See page 136 of the processors datasheet: http://www.atmel.com/Images/doc2549.pd
#define FUEL2_COMPARE OCR3B
#define FUEL3_COMPARE OCR3C
#define FUEL4_COMPARE OCR4B
#define FUEL5_COMPARE OCR3A //Shared with FUEL1
#define IGN1_COMPARE OCR5A
#define IGN2_COMPARE OCR5B
@ -160,58 +162,59 @@ See page 136 of the processors datasheet: http://www.atmel.com/Images/doc2549.pd
#define uS_TO_TIMER_COMPARE_SLOW(uS) ((uS * 15) >> 5)
#elif defined(CORE_STM32)
#include "HardwareTimer.h"
//Placeholders ONLY!
//https://visualgdb.com/tutorials/arm/stm32/timers/hal/
//https://github.com/rogerclarkmelbourne/Arduino_STM32/blob/master/STM32F4/cores/maple/libmaple/timer.h#L51
#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
#define FUEL3_COUNTER (TIMER2->regs).gen->CNT
#define FUEL4_COUNTER (TIMER2->regs).gen->CNT
#define FUEL1_COUNTER (TIM2)->CNT
#define FUEL2_COUNTER (TIM2)->CNT
#define FUEL3_COUNTER (TIM2)->CNT
#define FUEL4_COUNTER (TIM2)->CNT
#define FUEL5_COUNTER (TIM2)->CNT
#define IGN1_COUNTER (TIMER3->regs).gen->CNT
#define IGN2_COUNTER (TIMER3->regs).gen->CNT
#define IGN3_COUNTER (TIMER3->regs).gen->CNT
#define IGN4_COUNTER (TIMER3->regs).gen->CNT
#define IGN5_COUNTER (TIMER1->regs).gen->CNT
#define IGN1_COUNTER (TIM3)->CNT
#define IGN2_COUNTER (TIM3)->CNT
#define IGN3_COUNTER (TIM3)->CNT
#define IGN4_COUNTER (TIM3)->CNT
#define IGN5_COUNTER (TIM3)->CNT
#define FUEL1_COMPARE (TIMER2->regs).gen->CCR1
#define FUEL2_COMPARE (TIMER2->regs).gen->CCR2
#define FUEL3_COMPARE (TIMER2->regs).gen->CCR3
#define FUEL4_COMPARE (TIMER2->regs).gen->CCR4
#define FUEL1_COMPARE (TIM2)->CCR1
#define FUEL2_COMPARE (TIM2)->CCR2
#define FUEL3_COMPARE (TIM2)->CCR3
#define FUEL4_COMPARE (TIM2)->CCR4
#define IGN1_COMPARE (TIMER3->regs).gen->CCR1
#define IGN2_COMPARE (TIMER3->regs).gen->CCR2
#define IGN3_COMPARE (TIMER3->regs).gen->CCR3
#define IGN4_COMPARE (TIMER3->regs).gen->CCR4
#define IGN5_COMPARE (TIMER1->regs).gen->CCR1
#define IGN1_COMPARE (TIM3)->CCR1
#define IGN2_COMPARE (TIM3)->CCR2
#define IGN3_COMPARE (TIM3)->CCR3
#define IGN4_COMPARE (TIM3)->CCR4
#define IGN5_COMPARE (TIM3)->CCR1
//https://github.com/rogerclarkmelbourne/Arduino_STM32/blob/754bc2969921f1ef262bd69e7faca80b19db7524/STM32F1/system/libmaple/include/libmaple/timer.h#L444
#define FUEL1_TIMER_ENABLE() (TIMER2->regs).gen->CCER |= TIMER_CCER_CC1E
#define FUEL2_TIMER_ENABLE() (TIMER2->regs).gen->CCER |= TIMER_CCER_CC2E
#define FUEL3_TIMER_ENABLE() (TIMER2->regs).gen->CCER |= TIMER_CCER_CC3E
#define FUEL4_TIMER_ENABLE() (TIMER2->regs).gen->CCER |= TIMER_CCER_CC4E
#define FUEL1_TIMER_ENABLE() (TIM2)->CCER |= TIM_CCER_CC1E
#define FUEL2_TIMER_ENABLE() (TIM2)->CCER |= TIM_CCER_CC2E
#define FUEL3_TIMER_ENABLE() (TIM2)->CCER |= TIM_CCER_CC3E
#define FUEL4_TIMER_ENABLE() (TIM2)->CCER |= TIM_CCER_CC4E
#define IGN1_TIMER_ENABLE() (TIMER3->regs).gen->CCER |= TIMER_CCER_CC1E
#define IGN2_TIMER_ENABLE() (TIMER3->regs).gen->CCER |= TIMER_CCER_CC2E
#define IGN3_TIMER_ENABLE() (TIMER3->regs).gen->CCER |= TIMER_CCER_CC3E
#define IGN4_TIMER_ENABLE() (TIMER3->regs).gen->CCER |= TIMER_CCER_CC4E
#define IGN5_TIMER_ENABLE() (TIMER1->regs).gen->CCER |= TIMER_CCER_CC1E
#define IGN1_TIMER_ENABLE() (TIM3)->CCER |= TIM_CCER_CC1E
#define IGN2_TIMER_ENABLE() (TIM3)->CCER |= TIM_CCER_CC2E
#define IGN3_TIMER_ENABLE() (TIM3)->CCER |= TIM_CCER_CC3E
#define IGN4_TIMER_ENABLE() (TIM3)->CCER |= TIM_CCER_CC4E
#define IGN5_TIMER_ENABLE() (TIM1)->CCER |= TIM_CCER_CC1E
#define FUEL1_TIMER_DISABLE() (TIMER2->regs).gen->CCER &= ~TIMER_CCER_CC1E
#define FUEL2_TIMER_DISABLE() (TIMER2->regs).gen->CCER &= ~TIMER_CCER_CC2E
#define FUEL3_TIMER_DISABLE() (TIMER2->regs).gen->CCER &= ~TIMER_CCER_CC3E
#define FUEL4_TIMER_DISABLE() (TIMER2->regs).gen->CCER &= ~TIMER_CCER_CC4E
#define IGN1_TIMER_DISABLE() (TIMER3->regs).gen->CCER &= ~TIMER_CCER_CC1E
#define IGN2_TIMER_DISABLE() (TIMER3->regs).gen->CCER &= ~TIMER_CCER_CC2E
#define IGN3_TIMER_DISABLE() (TIMER3->regs).gen->CCER &= ~TIMER_CCER_CC3E
#define IGN4_TIMER_DISABLE() (TIMER3->regs).gen->CCER &= ~TIMER_CCER_CC4E
#define IGN5_TIMER_DISABLE() (TIMER1->regs).gen->CCER &= ~TIMER_CCER_CC1E
#define FUEL1_TIMER_DISABLE() (TIM2)->CCER &= ~TIM_CCER_CC1E
#define FUEL2_TIMER_DISABLE() (TIM2)->CCER &= ~TIM_CCER_CC2E
#define FUEL3_TIMER_DISABLE() (TIM2)->CCER &= ~TIM_CCER_CC3E
#define FUEL4_TIMER_DISABLE() (TIM2)->CCER &= ~TIM_CCER_CC4E
#define IGN1_TIMER_DISABLE() (TIM3)->CCER &= ~TIM_CCER_CC1E
#define IGN2_TIMER_DISABLE() (TIM3)->CCER &= ~TIM_CCER_CC2E
#define IGN3_TIMER_DISABLE() (TIM3)->CCER &= ~TIM_CCER_CC3E
#define IGN4_TIMER_DISABLE() (TIM3)->CCER &= ~TIM_CCER_CC4E
#define IGN5_TIMER_DISABLE() (TIM1)->CCER &= ~TIM_CCER_CC1E
#endif
void initialiseSchedulers();
@ -255,8 +258,12 @@ struct Schedule {
void (*StartCallback)(); //Start Callback function for schedule
void (*EndCallback)(); //Start Callback function for schedule
volatile unsigned long startTime; //The system time (in uS) that the schedule started
unsigned int startCompare; //The counter value of the timer when this will start
unsigned int endCompare;
volatile unsigned int startCompare; //The counter value of the timer when this will start
volatile unsigned int endCompare;
unsigned int nextStartCompare;
unsigned int nextEndCompare;
volatile bool hasNextSchedule = false;
};
volatile Schedule *timer3Aqueue[4];
@ -345,8 +352,11 @@ static inline unsigned int popQueue(volatile Schedule *queue[])
queue[2] = queue[3];
queue[3] = &nullSchedule;
if( queue[0]->Status == PENDING ) { return queue[0]->startCompare; }
else { return queue[0]->endCompare; }
unsigned int returnCompare;
if( queue[0]->Status == PENDING ) { returnCompare = queue[0]->startCompare; }
else { returnCompare = queue[0]->endCompare; }
return returnCompare;
}

View File

@ -87,9 +87,10 @@ void initialiseSchedulers()
FTM1_SC |= FTM_SC_PS(0b111);
//Setup the channels (See Pg 1014 of K64 DS).
//FTM0_C0SC &= ~FTM_CSC_ELSB; //Probably not needed as power on state should be 0
//FTM0_C0SC &= ~FTM_CSC_ELSA; //Probably not needed as power on state should be 0
//FTM0_C0SC &= ~FTM_CSC_DMA; //Probably not needed as power on state should be 0
//The are probably not needed as power on state should be 0
//FTM0_C0SC &= ~FTM_CSC_ELSB;
//FTM0_C0SC &= ~FTM_CSC_ELSA;
//FTM0_C0SC &= ~FTM_CSC_DMA;
FTM0_C0SC &= ~FTM_CSC_MSB; //According to Pg 965 of the K64 datasheet, this should not be needed as MSB is reset to 0 upon reset, but the channel interrupt fails to fire without it
FTM0_C0SC |= FTM_CSC_MSA; //Enable Compare mode
FTM0_C0SC |= FTM_CSC_CHIE; //Enable channel compare interrupt
@ -161,19 +162,20 @@ void initialiseSchedulers()
#elif defined(CORE_STM32)
//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
Timer1.setPrescaleFactor(((Timer1.getBaseFrequency() / 1000000) << 1) -1); //2us resolution
Timer2.setPrescaleFactor(((Timer2.getBaseFrequency() / 1000000) << 1) -1); //2us resolution
Timer3.setPrescaleFactor(((Timer3.getBaseFrequency() / 1000000) << 1) -1); //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);
Timer2.setMode(1, TIMER_OUTPUT_COMPARE);
Timer2.setMode(2, TIMER_OUTPUT_COMPARE);
Timer2.setMode(3, TIMER_OUTPUT_COMPARE);
Timer2.setMode(4, 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);
Timer1.setMode(TIMER_CH1, TIMER_OUTPUT_COMPARE);
Timer3.setMode(1, TIMER_OUTPUT_COMPARE);
Timer3.setMode(2, TIMER_OUTPUT_COMPARE);
Timer3.setMode(3, TIMER_OUTPUT_COMPARE);
Timer3.setMode(4, TIMER_OUTPUT_COMPARE);
Timer1.setMode(1, TIMER_OUTPUT_COMPARE);
Timer2.attachInterrupt(1, fuelSchedule1Interrupt);
Timer2.attachInterrupt(2, fuelSchedule2Interrupt);
@ -186,6 +188,9 @@ void initialiseSchedulers()
Timer3.attachInterrupt(4, ignitionSchedule4Interrupt);
Timer1.attachInterrupt(1, ignitionSchedule5Interrupt);
Timer1.resume();
Timer2.resume();
Timer3.resume();
#endif
fuelSchedule1.Status = OFF;
@ -223,68 +228,78 @@ timeout: The number of uS in the future that the startCallback should be trigger
duration: The number of uS after startCallback is called before endCallback is called
endCallback: This function is called once the duration time has been reached
*/
void setFuelSchedule1(void (*startCallback)(), unsigned long timeout, unsigned long duration, void(*endCallback)())
//void setFuelSchedule1(void (*startCallback)(), unsigned long timeout, unsigned long duration, void(*endCallback)())
void setFuelSchedule1(unsigned long timeout, unsigned long duration)
{
if(fuelSchedule1.Status != RUNNING) //Check that we're not already part way through a schedule
{
if(fuelSchedule1.Status == RUNNING) { return; } //Check that we're not already part way through a schedule
fuelSchedule1.StartCallback = startCallback; //Name the start callback function
fuelSchedule1.EndCallback = endCallback; //Name the end callback function
//Callbacks no longer used, but retained for now:
//fuelSchedule1.StartCallback = startCallback;
//fuelSchedule1.EndCallback = endCallback;
fuelSchedule1.duration = duration;
/*
* The following must be enclosed in the noInterupts block to avoid contention caused if the relevant interrupts fires before the state is fully set
* We need to calculate the value to reset the timer to (preload) in order to achieve the desired overflow time
* As the timer is ticking every 16uS (Time per Tick = (Prescale)*(1/Frequency))
* unsigned int absoluteTimeout = TCNT3 + (timeout / 16); //Each tick occurs every 16uS with the 256 prescaler, so divide the timeout by 16 to get ther required number of ticks. Add this to the current tick count to get the target time. This will automatically overflow as required
*/
noInterrupts();
fuelSchedule1.startCompare = FUEL1_COUNTER + uS_TO_TIMER_COMPARE_SLOW(timeout);
fuelSchedule1.endCompare = fuelSchedule1.startCompare + uS_TO_TIMER_COMPARE_SLOW(duration);
fuelSchedule1.Status = PENDING; //Turn this schedule on
fuelSchedule1.schedulesSet++; //Increment the number of times this schedule has been set
/*if(channel5InjEnabled) { FUEL1_COMPARE = setQueue(timer3Aqueue, &fuelSchedule1, &fuelSchedule5, FUEL1_COUNTER); } //Schedule 1 shares a timer with schedule 5
else { timer3Aqueue[0] = &fuelSchedule1; timer3Aqueue[1] = &fuelSchedule1; timer3Aqueue[2] = &fuelSchedule1; timer3Aqueue[3] = &fuelSchedule1; FUEL1_COMPARE = fuelSchedule1.startCompare; }*/
timer3Aqueue[0] = &fuelSchedule1; timer3Aqueue[1] = &fuelSchedule1; timer3Aqueue[2] = &fuelSchedule1; timer3Aqueue[3] = &fuelSchedule1; FUEL1_COMPARE = fuelSchedule1.startCompare;
interrupts();
FUEL1_TIMER_ENABLE();
//The following must be enclosed in the noInterupts block to avoid contention caused if the relevant interrupt fires before the state is fully set
noInterrupts();
fuelSchedule1.startCompare = FUEL1_COUNTER + uS_TO_TIMER_COMPARE_SLOW(timeout);
fuelSchedule1.endCompare = fuelSchedule1.startCompare + uS_TO_TIMER_COMPARE_SLOW(duration);
fuelSchedule1.Status = PENDING; //Turn this schedule on
fuelSchedule1.schedulesSet++; //Increment the number of times this schedule has been set
//Schedule 1 shares a timer with schedule 5
//if(channel5InjEnabled) { FUEL1_COMPARE = setQueue(timer3Aqueue, &fuelSchedule1, &fuelSchedule5, FUEL1_COUNTER); }
//else { timer3Aqueue[0] = &fuelSchedule1; timer3Aqueue[1] = &fuelSchedule1; timer3Aqueue[2] = &fuelSchedule1; timer3Aqueue[3] = &fuelSchedule1; FUEL1_COMPARE = fuelSchedule1.startCompare; }
//timer3Aqueue[0] = &fuelSchedule1; timer3Aqueue[1] = &fuelSchedule1; timer3Aqueue[2] = &fuelSchedule1; timer3Aqueue[3] = &fuelSchedule1;
FUEL1_COMPARE = fuelSchedule1.startCompare;
interrupts();
FUEL1_TIMER_ENABLE();
}
void setFuelSchedule2(void (*startCallback)(), unsigned long timeout, unsigned long duration, void(*endCallback)())
else
{
if(fuelSchedule2.Status == RUNNING) { return; } //Check that we're not already part way through a schedule
fuelSchedule2.StartCallback = startCallback; //Name the start callback function
fuelSchedule2.EndCallback = endCallback; //Name the end callback function
//If the schedule is already running, we can set the next schedule so it is ready to go
//This is required in cases of high rpm and high DC where there otherwise would not be enough time to set the schedule
fuelSchedule1.nextStartCompare = FUEL1_COUNTER + uS_TO_TIMER_COMPARE_SLOW(timeout);
fuelSchedule1.nextEndCompare = fuelSchedule1.nextStartCompare + uS_TO_TIMER_COMPARE_SLOW(duration);
fuelSchedule1.hasNextSchedule = true;
}
}
void setFuelSchedule2(unsigned long timeout, unsigned long duration)
{
if(fuelSchedule2.Status != RUNNING) //Check that we're not already part way through a schedule
{
//Callbacks no longer used, but retained for now:
//fuelSchedule2.StartCallback = startCallback;
//fuelSchedule2.EndCallback = endCallback;
fuelSchedule2.duration = duration;
/*
* The following must be enclosed in the noIntterupts block to avoid contention caused if the relevant interrupts fires before the state is fully set
* We need to calculate the value to reset the timer to (preload) in order to achieve the desired overflow time
* As the timer is ticking every 16uS (Time per Tick = (Prescale)*(1/Frequency))
* unsigned int absoluteTimeout = TCNT3 + (timeout / 16); //Each tick occurs every 16uS with the 256 prescaler, so divide the timeout by 16 to get ther required number of ticks. Add this to the current tick count to get the target time. This will automatically overflow as required
*/
noInterrupts();
fuelSchedule2.startCompare = FUEL2_COUNTER + uS_TO_TIMER_COMPARE_SLOW(timeout);
fuelSchedule2.endCompare = fuelSchedule2.startCompare + uS_TO_TIMER_COMPARE_SLOW(duration);
FUEL2_COMPARE = fuelSchedule2.startCompare; //Use the B copmare unit of timer 3
fuelSchedule2.Status = PENDING; //Turn this schedule on
fuelSchedule2.schedulesSet++; //Increment the number of times this schedule has been set
interrupts();
FUEL2_TIMER_ENABLE();
//The following must be enclosed in the noInterupts block to avoid contention caused if the relevant interrupt fires before the state is fully set
noInterrupts();
fuelSchedule2.startCompare = FUEL2_COUNTER + uS_TO_TIMER_COMPARE_SLOW(timeout);
fuelSchedule2.endCompare = fuelSchedule2.startCompare + uS_TO_TIMER_COMPARE_SLOW(duration);
FUEL2_COMPARE = fuelSchedule2.startCompare; //Use the B compare unit of timer 3
fuelSchedule2.Status = PENDING; //Turn this schedule on
fuelSchedule2.schedulesSet++; //Increment the number of times this schedule has been set
interrupts();
FUEL2_TIMER_ENABLE();
}
void setFuelSchedule3(void (*startCallback)(), unsigned long timeout, unsigned long duration, void(*endCallback)())
else
{
if(fuelSchedule3.Status == RUNNING) { return; } //Check that we're not already part way through a schedule
fuelSchedule3.StartCallback = startCallback; //Name the start callback function
fuelSchedule3.EndCallback = endCallback; //Name the end callback function
//If the schedule is already running, we can set the next schedule so it is ready to go
//This is required in cases of high rpm and high DC where there otherwise would not be enough time to set the schedule
fuelSchedule2.nextStartCompare = FUEL2_COUNTER + uS_TO_TIMER_COMPARE_SLOW(timeout);
fuelSchedule2.nextEndCompare = fuelSchedule2.nextStartCompare + uS_TO_TIMER_COMPARE_SLOW(duration);
fuelSchedule2.hasNextSchedule = true;
}
}
//void setFuelSchedule3(void (*startCallback)(), unsigned long timeout, unsigned long duration, void(*endCallback)())
void setFuelSchedule3(unsigned long timeout, unsigned long duration)
{
if(fuelSchedule3.Status != RUNNING)//Check that we're not already part way through a schedule
{
//Callbacks no longer used, but retained for now:
//fuelSchedule3.StartCallback = startCallback;
//fuelSchedule3.EndCallback = endCallback;
fuelSchedule3.duration = duration;
/*
* The following must be enclosed in the noIntterupts block to avoid contention caused if the relevant interrupts fires before the state is fully set
* We need to calculate the value to reset the timer to (preload) in order to achieve the desired overflow time
* As the timer is ticking every 16uS (Time per Tick = (Prescale)*(1/Frequency))
* unsigned int absoluteTimeout = TCNT3 + (timeout / 16); //Each tick occurs every 16uS with the 256 prescaler, so divide the timeout by 16 to get ther required number of ticks. Add this to the current tick count to get the target time. This will automatically overflow as required
*/
//The following must be enclosed in the noInterupts block to avoid contention caused if the relevant interrupt fires before the state is fully set
noInterrupts();
fuelSchedule3.startCompare = FUEL3_COUNTER + uS_TO_TIMER_COMPARE_SLOW(timeout);
fuelSchedule3.endCompare = fuelSchedule3.startCompare + uS_TO_TIMER_COMPARE_SLOW(duration);
@ -294,20 +309,26 @@ void setFuelSchedule3(void (*startCallback)(), unsigned long timeout, unsigned l
interrupts();
FUEL3_TIMER_ENABLE();
}
void setFuelSchedule4(void (*startCallback)(), unsigned long timeout, unsigned long duration, void(*endCallback)()) //Uses timer 4 compare B
else
{
if(fuelSchedule4.Status == RUNNING) { return; } //Check that we're not already part way through a schedule
fuelSchedule4.StartCallback = startCallback; //Name the start callback function
fuelSchedule4.EndCallback = endCallback; //Name the end callback function
//If the schedule is already running, we can set the next schedule so it is ready to go
//This is required in cases of high rpm and high DC where there otherwise would not be enough time to set the schedule
fuelSchedule3.nextStartCompare = FUEL3_COUNTER + uS_TO_TIMER_COMPARE_SLOW(timeout);
fuelSchedule3.nextEndCompare = fuelSchedule3.nextStartCompare + uS_TO_TIMER_COMPARE_SLOW(duration);
fuelSchedule3.hasNextSchedule = true;
}
}
//void setFuelSchedule4(void (*startCallback)(), unsigned long timeout, unsigned long duration, void(*endCallback)())
void setFuelSchedule4(unsigned long timeout, unsigned long duration) //Uses timer 4 compare B
{
if(fuelSchedule4.Status != RUNNING) //Check that we're not already part way through a schedule
{
//Callbacks no longer used, but retained for now:
//fuelSchedule4.StartCallback = startCallback;
//fuelSchedule4.EndCallback = endCallback;
fuelSchedule4.duration = duration;
/*
* The following must be enclosed in the noIntterupts block to avoid contention caused if the relevant interrupts fires before the state is fully set
* We need to calculate the value to reset the timer to (preload) in order to achieve the desired overflow time
* As the timer is ticking every 16uS (Time per Tick = (Prescale)*(1/Frequency))
* unsigned int absoluteTimeout = TCNT3 + (timeout / 16); //Each tick occurs every 16uS with the 256 prescaler, so divide the timeout by 16 to get ther required number of ticks. Add this to the current tick count to get the target time. This will automatically overflow as required
*/
//The following must be enclosed in the noInterupts block to avoid contention caused if the relevant interrupt fires before the state is fully set
noInterrupts();
fuelSchedule4.startCompare = FUEL4_COUNTER + uS_TO_TIMER_COMPARE_SLOW(timeout);
fuelSchedule4.endCompare = fuelSchedule4.startCompare + uS_TO_TIMER_COMPARE_SLOW(duration);
@ -317,45 +338,62 @@ void setFuelSchedule4(void (*startCallback)(), unsigned long timeout, unsigned l
interrupts();
FUEL4_TIMER_ENABLE();
}
else
{
//If the schedule is already running, we can set the next schedule so it is ready to go
//This is required in cases of high rpm and high DC where there otherwise would not be enough time to set the schedule
fuelSchedule4.nextStartCompare = FUEL4_COUNTER + uS_TO_TIMER_COMPARE_SLOW(timeout);
fuelSchedule4.nextEndCompare = fuelSchedule4.nextStartCompare + uS_TO_TIMER_COMPARE_SLOW(duration);
fuelSchedule4.hasNextSchedule = true;
}
}
void setFuelSchedule5(void (*startCallback)(), unsigned long timeout, unsigned long duration, void(*endCallback)())
{
if(fuelSchedule5.Status == RUNNING) { return; } //Check that we're not already part way through a schedule
if(fuelSchedule5.Status != RUNNING) //Check that we're not already part way through a schedule
{
fuelSchedule5.StartCallback = startCallback; //Name the start callback function
fuelSchedule5.EndCallback = endCallback; //Name the end callback function
fuelSchedule5.duration = duration;
//We need to calculate the value to reset the timer to (preload) in order to achieve the desired overflow time
//As the timer is ticking every 16uS (Time per Tick = (Prescale)*(1/Frequency))
//unsigned int absoluteTimeout = TCNT3 + (timeout / 16); //Each tick occurs every 16uS with the 256 prescaler, so divide the timeout by 16 to get ther required number of ticks. Add this to the current tick count to get the target time. This will automatically overflow as required
fuelSchedule5.StartCallback = startCallback; //Name the start callback function
fuelSchedule5.EndCallback = endCallback; //Name the end callback function
fuelSchedule5.duration = duration;
/*
* The following must be enclosed in the noIntterupts block to avoid contention caused if the relevant interrupts fires before the state is fully set
*/
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) || defined(__AVR_ATmega2561__)
noInterrupts();
fuelSchedule5.startCompare = TCNT3 + (timeout >> 4); //As above, but with bit shift instead of / 16
fuelSchedule5.endCompare = fuelSchedule5.startCompare + (duration >> 4);
fuelSchedule5.Status = PENDING; //Turn this schedule on
fuelSchedule5.schedulesSet++; //Increment the number of times this schedule has been set
OCR3A = setQueue(timer3Aqueue, &fuelSchedule1, &fuelSchedule5, TCNT3); //Schedule 1 shares a timer with schedule 5
interrupts();
TIMSK3 |= (1 << OCIE3A); //Turn on the A compare unit (ie turn on the interrupt)
#endif
/*
* The following must be enclosed in the noIntterupts block to avoid contention caused if the relevant interrupts fires before the state is fully set
*/
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) || defined(__AVR_ATmega2561__)
noInterrupts();
fuelSchedule5.startCompare = TCNT3 + (timeout >> 4); //As above, but with bit shift instead of / 16
fuelSchedule5.endCompare = fuelSchedule5.startCompare + (duration >> 4);
fuelSchedule5.Status = PENDING; //Turn this schedule on
fuelSchedule5.schedulesSet++; //Increment the number of times this schedule has been set
OCR3A = setQueue(timer3Aqueue, &fuelSchedule1, &fuelSchedule5, TCNT3); //Schedule 1 shares a timer with schedule 5
interrupts();
TIMSK3 |= (1 << OCIE3A); //Turn on the A compare unit (ie turn on the interrupt)
#endif
}
else
{
//If the schedule is already running, we can set the next schedule so it is ready to go
//This is required in cases of high rpm and high DC where there otherwise would not be enough time to set the schedule
fuelSchedule5.nextStartCompare = FUEL5_COUNTER + uS_TO_TIMER_COMPARE_SLOW(timeout);
fuelSchedule5.nextEndCompare = fuelSchedule5.nextStartCompare + uS_TO_TIMER_COMPARE_SLOW(duration);
fuelSchedule5.hasNextSchedule = true;
}
}
//Ignition schedulers use Timer 5
void setIgnitionSchedule1(void (*startCallback)(), unsigned long timeout, unsigned long duration, void(*endCallback)())
{
if(ignitionSchedule1.Status != RUNNING) //Check that we're not already part way through a schedule
{
if(ignitionSchedule1.Status == RUNNING) { return; } //Check that we're not already part way through a schedule
ignitionSchedule1.StartCallback = startCallback; //Name the start callback function
ignitionSchedule1.EndCallback = endCallback; //Name the start callback function
ignitionSchedule1.duration = duration;
//As the timer is ticking every 4uS (Time per Tick = (Prescale)*(1/Frequency))
if (timeout > MAX_TIMER_PERIOD) { timeout = MAX_TIMER_PERIOD - 1; } // If the timeout is >4x (Each tick represents 4uS) the maximum allowed value of unsigned int (65535), the timer compare value will overflow when appliedcausing erratic behaviour such as erroneous sparking.
//Need to check that the timeout doesn't exceed the overflow
uint16_t timeout_timer_compare;
if (timeout > MAX_TIMER_PERIOD) { timeout_timer_compare = uS_TO_TIMER_COMPARE( (MAX_TIMER_PERIOD - 1) ); } // If the timeout is >4x (Each tick represents 4uS) the maximum allowed value of unsigned int (65535), the timer compare value will overflow when appliedcausing erratic behaviour such as erroneous sparking.
else { timeout_timer_compare = uS_TO_TIMER_COMPARE(timeout); } //Normal case
noInterrupts();
ignitionSchedule1.startCompare = IGN1_COUNTER + uS_TO_TIMER_COMPARE(timeout); //As there is a tick every 4uS, there are timeout/4 ticks until the interrupt should be triggered ( >>2 divides by 4)
ignitionSchedule1.startCompare = IGN1_COUNTER + timeout_timer_compare; //As there is a tick every 4uS, there are timeout/4 ticks until the interrupt should be triggered ( >>2 divides by 4)
ignitionSchedule1.endCompare = ignitionSchedule1.startCompare + uS_TO_TIMER_COMPARE(duration);
IGN1_COMPARE = ignitionSchedule1.startCompare;
ignitionSchedule1.Status = PENDING; //Turn this schedule on
@ -363,19 +401,22 @@ void setIgnitionSchedule1(void (*startCallback)(), unsigned long timeout, unsign
interrupts();
IGN1_TIMER_ENABLE();
}
}
void setIgnitionSchedule2(void (*startCallback)(), unsigned long timeout, unsigned long duration, void(*endCallback)())
{
if(ignitionSchedule2.Status != RUNNING) //Check that we're not already part way through a schedule
{
if(ignitionSchedule2.Status == RUNNING) { return; } //Check that we're not already part way through a schedule
ignitionSchedule2.StartCallback = startCallback; //Name the start callback function
ignitionSchedule2.EndCallback = endCallback; //Name the start callback function
ignitionSchedule2.duration = duration;
//As the timer is ticking every 4uS (Time per Tick = (Prescale)*(1/Frequency))
if (timeout > MAX_TIMER_PERIOD) { timeout = MAX_TIMER_PERIOD - 1; } // If the timeout is >4x (Each tick represents 4uS) the maximum allowed value of unsigned int (65535), the timer compare value will overflow when appliedcausing erratic behaviour such as erroneous sparking.
//Need to check that the timeout doesn't exceed the overflow
uint16_t timeout_timer_compare;
if (timeout > MAX_TIMER_PERIOD) { timeout_timer_compare = uS_TO_TIMER_COMPARE( (MAX_TIMER_PERIOD - 1) ); } // If the timeout is >4x (Each tick represents 4uS) the maximum allowed value of unsigned int (65535), the timer compare value will overflow when appliedcausing erratic behaviour such as erroneous sparking.
else { timeout_timer_compare = uS_TO_TIMER_COMPARE(timeout); } //Normal case
noInterrupts();
ignitionSchedule2.startCompare = IGN2_COUNTER + uS_TO_TIMER_COMPARE(timeout); //As there is a tick every 4uS, there are timeout/4 ticks until the interrupt should be triggered ( >>2 divides by 4)
ignitionSchedule2.startCompare = IGN2_COUNTER + timeout_timer_compare; //As there is a tick every 4uS, there are timeout/4 ticks until the interrupt should be triggered ( >>2 divides by 4)
ignitionSchedule2.endCompare = ignitionSchedule2.startCompare + uS_TO_TIMER_COMPARE(duration);
IGN2_COMPARE = ignitionSchedule2.startCompare;
ignitionSchedule2.Status = PENDING; //Turn this schedule on
@ -383,19 +424,23 @@ void setIgnitionSchedule2(void (*startCallback)(), unsigned long timeout, unsign
interrupts();
IGN2_TIMER_ENABLE();
}
}
void setIgnitionSchedule3(void (*startCallback)(), unsigned long timeout, unsigned long duration, void(*endCallback)())
{
if(ignitionSchedule3.Status != RUNNING) //Check that we're not already part way through a schedule
{
if(ignitionSchedule3.Status == RUNNING) { return; } //Check that we're not already part way through a schedule
ignitionSchedule3.StartCallback = startCallback; //Name the start callback function
ignitionSchedule3.EndCallback = endCallback; //Name the start callback function
ignitionSchedule3.duration = duration;
//The timer is ticking every 4uS (Time per Tick = (Prescale)*(1/Frequency))
if (timeout > MAX_TIMER_PERIOD) { timeout = MAX_TIMER_PERIOD - 1; } // If the timeout is >4x (Each tick represents 4uS) the maximum allowed value of unsigned int (65535), the timer compare value will overflow when appliedcausing erratic behaviour such as erroneous sparking.
//Need to check that the timeout doesn't exceed the overflow
uint16_t timeout_timer_compare;
if (timeout > MAX_TIMER_PERIOD) { timeout_timer_compare = uS_TO_TIMER_COMPARE( (MAX_TIMER_PERIOD - 1) ); } // If the timeout is >4x (Each tick represents 4uS) the maximum allowed value of unsigned int (65535), the timer compare value will overflow when appliedcausing erratic behaviour such as erroneous sparking.
else { timeout_timer_compare = uS_TO_TIMER_COMPARE(timeout); } //Normal case
noInterrupts();
ignitionSchedule3.startCompare = IGN3_COUNTER + uS_TO_TIMER_COMPARE(timeout); //As there is a tick every 4uS, there are timeout/4 ticks until the interrupt should be triggered ( >>2 divides by 4)
ignitionSchedule3.startCompare = IGN3_COUNTER + timeout_timer_compare; //As there is a tick every 4uS, there are timeout/4 ticks until the interrupt should be triggered ( >>2 divides by 4)
ignitionSchedule3.endCompare = ignitionSchedule3.startCompare + uS_TO_TIMER_COMPARE(duration);
IGN3_COMPARE = ignitionSchedule3.startCompare;
ignitionSchedule3.Status = PENDING; //Turn this schedule on
@ -403,21 +448,23 @@ void setIgnitionSchedule3(void (*startCallback)(), unsigned long timeout, unsign
interrupts();
IGN3_TIMER_ENABLE();
}
}
void setIgnitionSchedule4(void (*startCallback)(), unsigned long timeout, unsigned long duration, void(*endCallback)())
{
if(ignitionSchedule4.Status != RUNNING) //Check that we're not already part way through a schedule
{
if(ignitionSchedule4.Status == RUNNING) { return; } //Check that we're not already part way through a schedule
ignitionSchedule4.StartCallback = startCallback; //Name the start callback function
ignitionSchedule4.EndCallback = endCallback; //Name the start callback function
ignitionSchedule4.duration = duration;
//We need to calculate the value to reset the timer to (preload) in order to achieve the desired overflow time
//The timer is ticking every 16uS (Time per Tick = (Prescale)*(1/Frequency))
//Note this is different to the other ignition timers
if (timeout > MAX_TIMER_PERIOD) { timeout = MAX_TIMER_PERIOD - 1; } // If the timeout is >4x (Each tick represents 4uS) the maximum allowed value of unsigned int (65535), the timer compare value will overflow when appliedcausing erratic behaviour such as erroneous sparking.
//Need to check that the timeout doesn't exceed the overflow
uint16_t timeout_timer_compare;
if (timeout > MAX_TIMER_PERIOD) { timeout_timer_compare = uS_TO_TIMER_COMPARE_SLOW( (MAX_TIMER_PERIOD - 1) ); } // If the timeout is >4x (Each tick represents 4uS) the maximum allowed value of unsigned int (65535), the timer compare value will overflow when appliedcausing erratic behaviour such as erroneous sparking.
else { timeout_timer_compare = uS_TO_TIMER_COMPARE_SLOW(timeout); } //Normal case
noInterrupts();
ignitionSchedule4.startCompare = IGN4_COUNTER + uS_TO_TIMER_COMPARE_SLOW(timeout);
ignitionSchedule4.startCompare = IGN4_COUNTER + timeout_timer_compare;
ignitionSchedule4.endCompare = ignitionSchedule4.startCompare + uS_TO_TIMER_COMPARE_SLOW(duration);
IGN4_COMPARE = ignitionSchedule4.startCompare;
ignitionSchedule4.Status = PENDING; //Turn this schedule on
@ -425,21 +472,23 @@ void setIgnitionSchedule4(void (*startCallback)(), unsigned long timeout, unsign
interrupts();
IGN4_TIMER_ENABLE();
}
}
void setIgnitionSchedule5(void (*startCallback)(), unsigned long timeout, unsigned long duration, void(*endCallback)())
{
if(ignitionSchedule5.Status != RUNNING)//Check that we're not already part way through a schedule
{
if(ignitionSchedule5.Status == RUNNING) { return; } //Check that we're not already part way through a schedule
ignitionSchedule5.StartCallback = startCallback; //Name the start callback function
ignitionSchedule5.EndCallback = endCallback; //Name the start callback function
ignitionSchedule5.duration = duration;
//We need to calculate the value to reset the timer to (preload) in order to achieve the desired overflow time
//The timer is ticking every 16uS (Time per Tick = (Prescale)*(1/Frequency))
//Note this is different to the other ignition timers
if (timeout > MAX_TIMER_PERIOD) { timeout = MAX_TIMER_PERIOD - 1; } // If the timeout is >4x (Each tick represents 4uS) the maximum allowed value of unsigned int (65535), the timer compare value will overflow when appliedcausing erratic behaviour such as erroneous sparking.
//Need to check that the timeout doesn't exceed the overflow
uint16_t timeout_timer_compare;
if (timeout > MAX_TIMER_PERIOD) { timeout_timer_compare = uS_TO_TIMER_COMPARE_SLOW( (MAX_TIMER_PERIOD - 1) ); } // If the timeout is >4x (Each tick represents 4uS) the maximum allowed value of unsigned int (65535), the timer compare value will overflow when appliedcausing erratic behaviour such as erroneous sparking.
else { timeout_timer_compare = uS_TO_TIMER_COMPARE_SLOW(timeout); } //Normal case
noInterrupts();
ignitionSchedule5.startCompare = IGN5_COUNTER + uS_TO_TIMER_COMPARE_SLOW(timeout);
ignitionSchedule5.startCompare = IGN5_COUNTER + timeout_timer_compare;
ignitionSchedule5.endCompare = ignitionSchedule5.startCompare + uS_TO_TIMER_COMPARE_SLOW(duration);
IGN5_COMPARE = ignitionSchedule5.startCompare;
ignitionSchedule5.Status = PENDING; //Turn this schedule on
@ -447,6 +496,7 @@ void setIgnitionSchedule5(void (*startCallback)(), unsigned long timeout, unsign
interrupts();
IGN5_TIMER_ENABLE();
}
}
/*******************************************************************************************************************************************************************************************************/
//This function (All 8 ISR functions that are below) gets called when either the start time or the duration time are reached
@ -459,20 +509,35 @@ ISR(TIMER3_COMPA_vect, ISR_NOBLOCK) //fuelSchedules 1 and 5
static inline void fuelSchedule1Interrupt() //Most ARM chips can simply call a function
#endif
{
if (timer3Aqueue[0]->Status == OFF) { FUEL1_TIMER_DISABLE(); return; } //Safety check. Turn off this output compare unit and return without performing any action
if (timer3Aqueue[0]->Status == PENDING) //Check to see if this schedule is turn on
if (fuelSchedule1.Status == PENDING) //Check to see if this schedule is turn on
{
timer3Aqueue[0]->StartCallback();
timer3Aqueue[0]->Status = RUNNING; //Set the status to be in progress (ie The start callback has been called, but not the end callback)
FUEL1_COMPARE = popQueue(timer3Aqueue);
//To use timer queue, change fuelShedule1 to timer3Aqueue[0];
if (configPage1.injLayout == INJ_SEMISEQUENTIAL) { openInjector1and4(); }
else { openInjector1(); }
fuelSchedule1.Status = RUNNING; //Set the status to be in progress (ie The start callback has been called, but not the end callback)
FUEL1_COMPARE = fuelSchedule1.endCompare;
}
else if (timer3Aqueue[0]->Status == RUNNING)
else if (fuelSchedule1.Status == RUNNING)
{
timer3Aqueue[0]->EndCallback();
timer3Aqueue[0]->Status = OFF; //Turn off the schedule
timer3Aqueue[0]->schedulesSet = 0;
FUEL1_COMPARE = popQueue(timer3Aqueue);
//timer3Aqueue[0]->EndCallback();
if (configPage1.injLayout == INJ_SEMISEQUENTIAL) { closeInjector1and4(); }
else { closeInjector1(); }
fuelSchedule1.Status = OFF; //Turn off the schedule
fuelSchedule1.schedulesSet = 0;
//FUEL1_COMPARE = fuelSchedule1.endCompare;
//If there is a next schedule queued up, activate it
if(fuelSchedule1.hasNextSchedule == true)
{
FUEL1_COMPARE = fuelSchedule1.nextStartCompare;
fuelSchedule1.endCompare = fuelSchedule1.nextEndCompare;
fuelSchedule1.Status = PENDING;
fuelSchedule1.schedulesSet = 1;
fuelSchedule1.hasNextSchedule = false;
}
else { FUEL1_TIMER_DISABLE(); }
}
else if (fuelSchedule1.Status == OFF) { FUEL1_TIMER_DISABLE(); } //Safety check. Turn off this output compare unit and return without performing any action
}
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) || defined(__AVR_ATmega2561__) //AVR chips use the ISR for this
@ -483,16 +548,30 @@ static inline void fuelSchedule2Interrupt() //Most ARM chips can simply call a f
{
if (fuelSchedule2.Status == PENDING) //Check to see if this schedule is turn on
{
fuelSchedule2.StartCallback();
//fuelSchedule2.StartCallback();
if (configPage1.injLayout == INJ_SEMISEQUENTIAL) { openInjector2and3(); }
else { openInjector2(); }
fuelSchedule2.Status = RUNNING; //Set the status to be in progress (ie The start callback has been called, but not the end callback)
FUEL2_COMPARE = fuelSchedule2.endCompare;
}
else if (fuelSchedule2.Status == RUNNING)
{
fuelSchedule2.EndCallback();
//fuelSchedule2.EndCallback();
if (configPage1.injLayout == INJ_SEMISEQUENTIAL) { closeInjector2and3(); }
else { closeInjector2(); }
fuelSchedule2.Status = OFF; //Turn off the schedule
fuelSchedule2.schedulesSet = 0;
FUEL2_TIMER_DISABLE();
//If there is a next schedule queued up, activate it
if(fuelSchedule2.hasNextSchedule == true)
{
FUEL2_COMPARE = fuelSchedule2.nextStartCompare;
fuelSchedule2.endCompare = fuelSchedule2.nextEndCompare;
fuelSchedule2.Status = PENDING;
fuelSchedule2.schedulesSet = 1;
fuelSchedule2.hasNextSchedule = false;
}
else { FUEL2_TIMER_DISABLE(); }
}
}
@ -504,16 +583,32 @@ static inline void fuelSchedule3Interrupt() //Most ARM chips can simply call a f
{
if (fuelSchedule3.Status == PENDING) //Check to see if this schedule is turn on
{
fuelSchedule3.StartCallback();
//fuelSchedule3.StartCallback();
//Hack for 5 cylinder
if(channel5InjEnabled) { openInjector3and5(); }
else { openInjector3(); }
fuelSchedule3.Status = RUNNING; //Set the status to be in progress (ie The start callback has been called, but not the end callback)
FUEL3_COMPARE = fuelSchedule3.endCompare;
}
else if (fuelSchedule3.Status == RUNNING)
{
fuelSchedule3.EndCallback();
//fuelSchedule3.EndCallback();
//Hack for 5 cylinder
if(channel5InjEnabled) { closeInjector3and5(); }
else { closeInjector3and5(); }
fuelSchedule3.Status = OFF; //Turn off the schedule
fuelSchedule3.schedulesSet = 0;
FUEL3_TIMER_DISABLE();
//If there is a next schedule queued up, activate it
if(fuelSchedule3.hasNextSchedule == true)
{
FUEL3_COMPARE = fuelSchedule3.nextStartCompare;
fuelSchedule3.endCompare = fuelSchedule3.nextEndCompare;
fuelSchedule3.Status = PENDING;
fuelSchedule3.schedulesSet = 1;
fuelSchedule3.hasNextSchedule = false;
}
else { FUEL3_TIMER_DISABLE(); }
}
}
@ -525,16 +620,28 @@ static inline void fuelSchedule4Interrupt() //Most ARM chips can simply call a f
{
if (fuelSchedule4.Status == PENDING) //Check to see if this schedule is turn on
{
fuelSchedule4.StartCallback();
//fuelSchedule4.StartCallback();
openInjector4();
fuelSchedule4.Status = RUNNING; //Set the status to be in progress (ie The start callback has been called, but not the end callback)
FUEL4_COMPARE = fuelSchedule4.endCompare;
}
else if (fuelSchedule4.Status == RUNNING)
{
fuelSchedule4.EndCallback();
//fuelSchedule4.EndCallback();
closeInjector4();
fuelSchedule4.Status = OFF; //Turn off the schedule
fuelSchedule4.schedulesSet = 0;
FUEL4_TIMER_DISABLE();
//If there is a next schedule queued up, activate it
if(fuelSchedule4.hasNextSchedule == true)
{
FUEL4_COMPARE = fuelSchedule4.nextStartCompare;
fuelSchedule4.endCompare = fuelSchedule4.nextEndCompare;
fuelSchedule4.Status = PENDING;
fuelSchedule4.schedulesSet = 1;
fuelSchedule4.hasNextSchedule = false;
}
else { FUEL4_TIMER_DISABLE(); }
}
}
@ -550,7 +657,7 @@ static inline void ignitionSchedule1Interrupt() //Most ARM chips can simply call
ignitionSchedule1.Status = RUNNING; //Set the status to be in progress (ie The start callback has been called, but not the end callback)
ignitionSchedule1.startTime = micros();
ign1LastRev = currentStatus.startRevolutions;
IGN1_COMPARE = ignitionSchedule1.endCompare; //OCR5A = TCNT5 + (ignitionSchedule1.duration >> 2); //Divide by 4
IGN1_COMPARE = ignitionSchedule1.endCompare;
}
else if (ignitionSchedule1.Status == RUNNING)
{
@ -622,7 +729,7 @@ static inline void ignitionSchedule4Interrupt() //Most ARM chips can simply call
ignitionSchedule4.Status = RUNNING; //Set the status to be in progress (ie The start callback has been called, but not the end callback)
ignitionSchedule4.startTime = micros();
ign4LastRev = currentStatus.startRevolutions;
IGN4_COMPARE = ignitionSchedule4.endCompare; //OCR4A = TCNT4 + (ignitionSchedule4.duration >> 4); //Divide by 16
IGN4_COMPARE = ignitionSchedule4.endCompare;
}
else if (ignitionSchedule4.Status == RUNNING)
{
@ -663,15 +770,24 @@ static inline void ignitionSchedule5Interrupt() //Most ARM chips can simply call
#if defined(CORE_TEENSY)
void ftm0_isr(void)
{
//Use separate variables for each test to ensure conversion to bool
bool interrupt1 = (FTM0_C0SC & FTM_CSC_CHF);
bool interrupt2 = (FTM0_C1SC & FTM_CSC_CHF);
bool interrupt3 = (FTM0_C2SC & FTM_CSC_CHF);
bool interrupt4 = (FTM0_C3SC & FTM_CSC_CHF);
bool interrupt5 = (FTM0_C4SC & FTM_CSC_CHF);
bool interrupt6 = (FTM0_C5SC & FTM_CSC_CHF);
bool interrupt7 = (FTM0_C6SC & FTM_CSC_CHF);
bool interrupt8 = (FTM0_C7SC & FTM_CSC_CHF);
if(FTM0_C0SC & FTM_CSC_CHF) { FTM0_C0SC &= ~FTM_CSC_CHF; fuelSchedule1Interrupt(); }
else if(FTM0_C1SC & FTM_CSC_CHF) { FTM0_C1SC &= ~FTM_CSC_CHF; fuelSchedule2Interrupt(); }
else if(FTM0_C2SC & FTM_CSC_CHF) { FTM0_C2SC &= ~FTM_CSC_CHF; fuelSchedule3Interrupt(); }
else if(FTM0_C3SC & FTM_CSC_CHF) { FTM0_C3SC &= ~FTM_CSC_CHF; fuelSchedule4Interrupt(); }
else if(FTM0_C4SC & FTM_CSC_CHF) { FTM0_C4SC &= ~FTM_CSC_CHF; ignitionSchedule1Interrupt(); }
else if(FTM0_C5SC & FTM_CSC_CHF) { FTM0_C5SC &= ~FTM_CSC_CHF; ignitionSchedule2Interrupt(); }
else if(FTM0_C6SC & FTM_CSC_CHF) { FTM0_C6SC &= ~FTM_CSC_CHF; ignitionSchedule3Interrupt(); }
else if(FTM0_C7SC & FTM_CSC_CHF) { FTM0_C7SC &= ~FTM_CSC_CHF; ignitionSchedule4Interrupt(); }
if(interrupt1) { FTM0_C0SC &= ~FTM_CSC_CHF; fuelSchedule1Interrupt(); }
else if(interrupt2) { FTM0_C1SC &= ~FTM_CSC_CHF; fuelSchedule2Interrupt(); }
else if(interrupt3) { FTM0_C2SC &= ~FTM_CSC_CHF; fuelSchedule3Interrupt(); }
else if(interrupt4) { FTM0_C3SC &= ~FTM_CSC_CHF; fuelSchedule4Interrupt(); }
else if(interrupt5) { FTM0_C4SC &= ~FTM_CSC_CHF; ignitionSchedule1Interrupt(); }
else if(interrupt6) { FTM0_C5SC &= ~FTM_CSC_CHF; ignitionSchedule2Interrupt(); }
else if(interrupt7) { FTM0_C6SC &= ~FTM_CSC_CHF; ignitionSchedule3Interrupt(); }
else if(interrupt8) { FTM0_C7SC &= ~FTM_CSC_CHF; ignitionSchedule4Interrupt(); }
}
#endif

View File

@ -12,6 +12,7 @@
#define ADCFILTER_O2 128
#define ADCFILTER_BAT 128
#define ADCFILTER_MAP 20 //This is only used on Instantaneous MAP readings and is intentionally very weak to allow for faster response
#define ADCFILTER_BARO 64
#define BARO_MIN 87
#define BARO_MAX 108
@ -38,10 +39,9 @@ byte MAPcurRev; //Tracks which revolution we're sampling on
void instanteneousMAPReading();
void readMAP();
void readBaro();
void flexPulse();
unsigned int tempReading;
#if defined(ANALOG_ISR)
//Analog ISR interrupt routine
/*
@ -105,4 +105,4 @@ ISR(ADC_vect)
}
#endif
#endif // SENSORS_H
#endif // SENSORS_H

View File

@ -49,6 +49,7 @@ MAPcount = 0;
void instanteneousMAPReading()
{
unsigned int tempReading;
//Instantaneous MAP readings
#if defined(ANALOG_ISR_MAP)
tempReading = AnChannel[pinMAP-A0];
@ -62,13 +63,14 @@ void instanteneousMAPReading()
currentStatus.mapADC = ADC_FILTER(tempReading, ADCFILTER_MAP, currentStatus.mapADC); //Very weak filter
currentStatus.MAP = fastResize(currentStatus.mapADC, configPage1.mapMax); //Get the current MAP value
currentStatus.MAP = fastMap10Bit(currentStatus.mapADC, configPage1.mapMin, configPage1.mapMax); //Get the current MAP value
if(currentStatus.MAP < 0) { currentStatus.MAP = 0; } //Sanity check
}
void readMAP()
{
unsigned int tempReading;
//MAP Sampling system
switch(configPage1.mapSample)
{
@ -106,7 +108,8 @@ void readMAP()
if( (MAPrunningValue != 0) && (MAPcount != 0) )
{
currentStatus.mapADC = ldiv(MAPrunningValue, MAPcount).quot;
currentStatus.MAP = fastResize(currentStatus.mapADC, configPage1.mapMax); //Get the current MAP value
currentStatus.MAP = fastMap10Bit(currentStatus.mapADC, configPage1.mapMin, configPage1.mapMax); //Get the current MAP value
if(currentStatus.MAP < 0) { currentStatus.MAP = 0; } //Sanity check
MAPcurRev = currentStatus.startRevolutions; //Reset the current rev count
MAPrunningValue = 0;
MAPcount = 0;
@ -140,7 +143,8 @@ void readMAP()
{
//Reaching here means that the last cylce has completed and the MAP value should be calculated
currentStatus.mapADC = MAPrunningValue;
currentStatus.MAP = fastResize(currentStatus.mapADC, configPage1.mapMax); //Get the current MAP value
currentStatus.MAP = fastMap10Bit(currentStatus.mapADC, configPage1.mapMin, configPage1.mapMax); //Get the current MAP value
if(currentStatus.MAP < 0) { currentStatus.MAP = 0; } //Sanity check
MAPcurRev = currentStatus.startRevolutions; //Reset the current rev count
MAPrunningValue = 1023; //Reset the latest value so the next reading will always be lower
}
@ -160,10 +164,10 @@ void readTPS()
currentStatus.TPSlast = currentStatus.TPS;
currentStatus.TPSlast_time = currentStatus.TPS_time;
#if defined(ANALOG_ISR)
byte tempTPS = fastResize(AnChannel[pinTPS-A0], 255); //Get the current raw TPS ADC value and map it into a byte
byte tempTPS = fastMap1023toX(AnChannel[pinTPS-A0], 255); //Get the current raw TPS ADC value and map it into a byte
#else
analogRead(pinTPS);
byte tempTPS = fastResize(analogRead(pinTPS), 255); //Get the current raw TPS ADC value and map it into a byte
byte tempTPS = fastMap1023toX(analogRead(pinTPS), 255); //Get the current raw TPS ADC value and map it into a byte
#endif
currentStatus.tpsADC = ADC_FILTER(tempTPS, ADCFILTER_TPS, currentStatus.tpsADC);
//Check that the ADC values fall within the min and max ranges (Should always be the case, but noise can cause these to fluctuate outside the defined range).
@ -176,11 +180,12 @@ void readTPS()
void readCLT()
{
unsigned int tempReading;
#if defined(ANALOG_ISR)
tempReading = fastResize(AnChannel[pinCLT-A0], 511); //Get the current raw CLT value
tempReading = fastMap1023toX(AnChannel[pinCLT-A0], 511); //Get the current raw CLT value
#else
tempReading = analogRead(pinCLT);
tempReading = fastResize(analogRead(pinCLT), 511); //Get the current raw CLT value
tempReading = fastMap1023toX(analogRead(pinCLT), 511); //Get the current raw CLT value
#endif
currentStatus.cltADC = ADC_FILTER(tempReading, ADCFILTER_CLT, currentStatus.cltADC);
currentStatus.coolant = cltCalibrationTable[currentStatus.cltADC] - CALIBRATION_TEMPERATURE_OFFSET; //Temperature calibration values are stored as positive bytes. We subtract 40 from them to allow for negative temperatures
@ -188,23 +193,44 @@ void readCLT()
void readIAT()
{
unsigned int tempReading;
#if defined(ANALOG_ISR)
tempReading = fastResize(AnChannel[pinIAT-A0], 511); //Get the current raw IAT value
tempReading = fastMap1023toX(AnChannel[pinIAT-A0], 511); //Get the current raw IAT value
#else
tempReading = analogRead(pinIAT);
tempReading = fastResize(analogRead(pinIAT), 511); //Get the current raw IAT value
tempReading = fastMap1023toX(analogRead(pinIAT), 511); //Get the current raw IAT value
#endif
currentStatus.iatADC = ADC_FILTER(tempReading, ADCFILTER_IAT, currentStatus.iatADC);
currentStatus.IAT = iatCalibrationTable[currentStatus.iatADC] - CALIBRATION_TEMPERATURE_OFFSET;
}
void readBaro()
{
if ( configPage3.useExtBaro != 0 )
{
int tempReading;
// readings
#if defined(ANALOG_ISR_MAP)
tempReading = AnChannel[pinBaro-A0];
#else
tempReading = analogRead(pinBaro);
tempReading = analogRead(pinBaro);
#endif
currentStatus.baroADC = ADC_FILTER(tempReading, ADCFILTER_BARO, currentStatus.baroADC); //Very weak filter
currentStatus.baro = fastMap1023toX(currentStatus.baroADC, configPage1.mapMax); //Get the current MAP value
}
}
void readO2()
{
unsigned int tempReading;
#if defined(ANALOG_ISR)
tempReading = fastResize(AnChannel[pinO2-A0], 511); //Get the current O2 value.
tempReading = fastMap1023toX(AnChannel[pinO2-A0], 511); //Get the current O2 value.
#else
tempReading = analogRead(pinO2);
tempReading = fastResize(analogRead(pinO2), 511); //Get the current O2 value.
tempReading = fastMap1023toX(analogRead(pinO2), 511); //Get the current O2 value.
#endif
currentStatus.O2ADC = ADC_FILTER(tempReading, ADCFILTER_O2, currentStatus.O2ADC);
currentStatus.O2 = o2CalibrationTable[currentStatus.O2ADC];
@ -218,11 +244,12 @@ void readO2()
void readBat()
{
unsigned int tempReading;
#if defined(ANALOG_ISR)
tempReading = fastResize(AnChannel[pinBat-A0], 245); //Get the current raw Battery value. Permissible values are from 0v to 24.5v (245)
tempReading = fastMap1023toX(AnChannel[pinBat-A0], 245); //Get the current raw Battery value. Permissible values are from 0v to 24.5v (245)
#else
tempReading = analogRead(pinBat);
tempReading = fastResize(analogRead(pinBat), 245); //Get the current raw Battery value. Permissible values are from 0v to 24.5v (245)
tempReading = fastMap1023toX(analogRead(pinBat), 245); //Get the current raw Battery value. Permissible values are from 0v to 24.5v (245)
#endif
currentStatus.battery10 = ADC_FILTER(tempReading, ADCFILTER_BAT, currentStatus.battery10);
}
@ -234,4 +261,4 @@ void readBat()
void flexPulse()
{
++flexCounter;
}
}

View File

@ -54,6 +54,7 @@ struct config2 configPage2;
struct config3 configPage3;
struct config4 configPage4;
struct config10 configPage10;
struct config11 configPage11;
int req_fuel_uS, inj_opentime_uS;
@ -70,6 +71,7 @@ void (*trigger)(); //Pointer for the trigger function (Gets pointed to the relev
void (*triggerSecondary)(); //Pointer for the secondary trigger function (Gets pointed to the relevant decoder)
uint16_t (*getRPM)(); //Pointer to the getRPM function (Gets pointed to the relevant decoder)
int (*getCrankAngle)(int); //Pointer to the getCrank Angle function (Gets pointed to the relevant decoder)
void (*triggerSetEndTeeth)(); //Pointer to the triggerSetEndTeeth function of each decoder
byte cltCalibrationTable[CALIBRATION_TABLE_SIZE];
byte iatCalibrationTable[CALIBRATION_TABLE_SIZE];
@ -85,7 +87,8 @@ unsigned long currentLoopTime; //The time the current loop started (uS)
unsigned long previousLoopTime; //The time the previous loop started (uS)
int CRANK_ANGLE_MAX = 720;
int CRANK_ANGLE_MAX_IGN = 360, CRANK_ANGLE_MAX_INJ = 360; // The number of crank degrees that the system track over. 360 for wasted / timed batch and 720 for sequential
int CRANK_ANGLE_MAX_IGN = 360;
int CRANK_ANGLE_MAX_INJ = 360; // The number of crank degrees that the system track over. 360 for wasted / timed batch and 720 for sequential
static byte coilHIGH = HIGH;
static byte coilLOW = LOW;
@ -97,6 +100,7 @@ byte deltaToothCount = 0; //The last tooth that was used with the deltaV calc
int rpmDelta;
byte ignitionCount;
uint16_t fixedCrankingOverride = 0;
int16_t lastAdvance; //Stores the previous advance figure to track changes.
bool clutchTrigger;
bool previousClutchTrigger;
@ -152,7 +156,6 @@ void setup()
loadConfig();
doUpdates(); //Check if any data items need updating (Occurs ith firmware updates)
//Serial.begin(115200);
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) //ATmega2561 does not have Serial3
if (configPage10.enable_canbus == 1) { Serial3.begin(115200); }
#elif defined(CORE_STM32)
@ -183,6 +186,10 @@ void setup()
WUETable.xSize = 10;
WUETable.values = configPage1.wueValues;
WUETable.axisX = configPage2.wueBins;
crankingEnrichTable.valueSize = SIZE_BYTE;
crankingEnrichTable.xSize = 4;
crankingEnrichTable.values = configPage11.crankingEnrichValues;
crankingEnrichTable.axisX = configPage11.crankingEnrichBins;
dwellVCorrectionTable.valueSize = SIZE_BYTE;
dwellVCorrectionTable.xSize = 6;
@ -229,22 +236,31 @@ void setup()
//Lookup the current MAP reading for barometric pressure
readMAP();
/*
* The highest sea-level pressure on Earth occurs in Siberia, where the Siberian High often attains a sea-level pressure above 105 kPa;
* with record highs close to 108.5 kPa.
* The lowest measurable sea-level pressure is found at the centers of tropical cyclones and tornadoes, with a record low of 87 kPa;
*/
if ((currentStatus.MAP >= BARO_MIN) && (currentStatus.MAP <= BARO_MAX)) //Check if engine isn't running
//barometric reading can be taken from either an external sensor if enabled, or simply by using the initial MAP value
if ( configPage3.useExtBaro != 0 )
{
currentStatus.baro = currentStatus.MAP;
readBaro();
EEPROM.update(EEPROM_LAST_BARO, currentStatus.baro);
}
else
{
//Attempt to use the last known good baro reading from EEPROM
if ((EEPROM.read(EEPROM_LAST_BARO) >= BARO_MIN) && (EEPROM.read(EEPROM_LAST_BARO) <= BARO_MAX)) //Make sure it's not invalid (Possible on first run etc)
{ currentStatus.baro = EEPROM.read(EEPROM_LAST_BARO); } //last baro correction
else { currentStatus.baro = 100; } //Final fall back position.
/*
* The highest sea-level pressure on Earth occurs in Siberia, where the Siberian High often attains a sea-level pressure above 105 kPa;
* with record highs close to 108.5 kPa.
* The lowest measurable sea-level pressure is found at the centers of tropical cyclones and tornadoes, with a record low of 87 kPa;
*/
if ((currentStatus.MAP >= BARO_MIN) && (currentStatus.MAP <= BARO_MAX)) //Check if engine isn't running
{
currentStatus.baro = currentStatus.MAP;
EEPROM.update(EEPROM_LAST_BARO, currentStatus.baro);
}
else
{
//Attempt to use the last known good baro reading from EEPROM
if ((EEPROM.read(EEPROM_LAST_BARO) >= BARO_MIN) && (EEPROM.read(EEPROM_LAST_BARO) <= BARO_MAX)) //Make sure it's not invalid (Possible on first run etc)
{ currentStatus.baro = EEPROM.read(EEPROM_LAST_BARO); } //last baro correction
else { currentStatus.baro = 100; } //Final fall back position.
}
}
//Perform all initialisations
@ -341,6 +357,7 @@ void setup()
triggerSecondary = triggerSec_missingTooth;
getRPM = getRPM_missingTooth;
getCrankAngle = getCrankAngle_missingTooth;
triggerSetEndTeeth = triggerSetEndTeeth_missingTooth;
if(configPage2.TrigEdge == 0) { attachInterrupt(triggerInterrupt, trigger, RISING); } // Attach the crank trigger wheel interrupt (Hall sensor drags to ground when triggering)
else { attachInterrupt(triggerInterrupt, trigger, FALLING); }
@ -354,6 +371,7 @@ void setup()
trigger = triggerPri_BasicDistributor;
getRPM = getRPM_BasicDistributor;
getCrankAngle = getCrankAngle_BasicDistributor;
triggerSetEndTeeth = triggerSetEndTeeth_BasicDistributor;
if(configPage2.TrigEdge == 0) { attachInterrupt(triggerInterrupt, trigger, RISING); } // Attach the crank trigger wheel interrupt (Hall sensor drags to ground when triggering)
else { attachInterrupt(triggerInterrupt, trigger, FALLING); }
@ -364,6 +382,7 @@ void setup()
trigger = triggerPri_DualWheel;
getRPM = getRPM_DualWheel;
getCrankAngle = getCrankAngle_DualWheel;
triggerSetEndTeeth = triggerSetEndTeeth_DualWheel;
if(configPage2.TrigEdge == 0) { attachInterrupt(triggerInterrupt, trigger, RISING); } // Attach the crank trigger wheel interrupt (Hall sensor drags to ground when triggering)
else { attachInterrupt(triggerInterrupt, trigger, FALLING); }
@ -376,6 +395,7 @@ void setup()
trigger = triggerPri_GM7X;
getRPM = getRPM_GM7X;
getCrankAngle = getCrankAngle_GM7X;
triggerSetEndTeeth = triggerSetEndTeeth_GM7X;
if(configPage2.TrigEdge == 0) { attachInterrupt(triggerInterrupt, trigger, RISING); } // Attach the crank trigger wheel interrupt (Hall sensor drags to ground when triggering)
else { attachInterrupt(triggerInterrupt, trigger, FALLING); }
@ -386,6 +406,7 @@ void setup()
trigger = triggerPri_4G63;
getRPM = getRPM_4G63;
getCrankAngle = getCrankAngle_4G63;
triggerSetEndTeeth = triggerSetEndTeeth_4G63;
//These may both need to change, not sure
if(configPage2.TrigEdge == 0)
@ -405,6 +426,7 @@ void setup()
trigger = triggerPri_24X;
getRPM = getRPM_24X;
getCrankAngle = getCrankAngle_24X;
triggerSetEndTeeth = triggerSetEndTeeth_24X;
if(configPage2.TrigEdge == 0) { attachInterrupt(triggerInterrupt, trigger, RISING); } // Attach the crank trigger wheel interrupt (Hall sensor drags to ground when triggering)
else { attachInterrupt(triggerInterrupt, trigger, FALLING); } // Primary trigger connects to
@ -416,6 +438,7 @@ void setup()
trigger = triggerPri_Jeep2000;
getRPM = getRPM_Jeep2000;
getCrankAngle = getCrankAngle_Jeep2000;
triggerSetEndTeeth = triggerSetEndTeeth_Jeep2000;
if(configPage2.TrigEdge == 0) { attachInterrupt(triggerInterrupt, trigger, RISING); } // Attach the crank trigger wheel interrupt (Hall sensor drags to ground when triggering)
else { attachInterrupt(triggerInterrupt, trigger, FALLING); } // Primary trigger connects to
@ -427,6 +450,7 @@ void setup()
trigger = triggerPri_Audi135;
getRPM = getRPM_Audi135;
getCrankAngle = getCrankAngle_Audi135;
triggerSetEndTeeth = triggerSetEndTeeth_Audi135;
if(configPage2.TrigEdge == 0) { attachInterrupt(triggerInterrupt, trigger, RISING); } // Attach the crank trigger wheel interrupt (Hall sensor drags to ground when triggering)
else { attachInterrupt(triggerInterrupt, trigger, FALLING); }
@ -438,6 +462,7 @@ void setup()
trigger = triggerPri_HondaD17;
getRPM = getRPM_HondaD17;
getCrankAngle = getCrankAngle_HondaD17;
triggerSetEndTeeth = triggerSetEndTeeth_HondaD17;
if(configPage2.TrigEdge == 0) { attachInterrupt(triggerInterrupt, trigger, RISING); } // Attach the crank trigger wheel interrupt (Hall sensor drags to ground when triggering)
else { attachInterrupt(triggerInterrupt, trigger, FALLING); } // Primary trigger connects to
@ -449,6 +474,7 @@ void setup()
trigger = triggerPri_Miata9905;
getRPM = getRPM_Miata9905;
getCrankAngle = getCrankAngle_Miata9905;
triggerSetEndTeeth = triggerSetEndTeeth_Miata9905;
//These may both need to change, not sure
if(configPage2.TrigEdge == 0)
@ -468,6 +494,7 @@ void setup()
trigger = triggerPri_MazdaAU;
getRPM = getRPM_MazdaAU;
getCrankAngle = getCrankAngle_MazdaAU;
triggerSetEndTeeth = triggerSetEndTeeth_MazdaAU;
if(configPage2.TrigEdge == 0) { attachInterrupt(triggerInterrupt, trigger, RISING); } // Attach the crank trigger wheel interrupt (Hall sensor drags to ground when triggering)
else { attachInterrupt(triggerInterrupt, trigger, FALLING); } // Primary trigger connects to
@ -479,6 +506,7 @@ void setup()
trigger = triggerPri_DualWheel; //Is identical to the dual wheel decoder, so that is used. Same goes for the secondary below
getRPM = getRPM_non360;
getCrankAngle = getCrankAngle_non360;
triggerSetEndTeeth = triggerSetEndTeeth_Non360;
if(configPage2.TrigEdge == 0) { attachInterrupt(triggerInterrupt, trigger, RISING); } // Attach the crank trigger wheel interrupt (Hall sensor drags to ground when triggering)
else { attachInterrupt(triggerInterrupt, trigger, FALLING); }
@ -490,6 +518,7 @@ void setup()
trigger = triggerPri_Nissan360;
getRPM = getRPM_Nissan360;
getCrankAngle = getCrankAngle_Nissan360;
triggerSetEndTeeth = triggerSetEndTeeth_Nissan360;
if(configPage2.TrigEdge == 0) { attachInterrupt(triggerInterrupt, trigger, RISING); } // Attach the crank trigger wheel interrupt (Hall sensor drags to ground when triggering)
else { attachInterrupt(triggerInterrupt, trigger, FALLING); }
@ -501,6 +530,7 @@ void setup()
trigger = triggerPri_Subaru67;
getRPM = getRPM_Subaru67;
getCrankAngle = getCrankAngle_Subaru67;
triggerSetEndTeeth = triggerSetEndTeeth_Subaru67;
if(configPage2.TrigEdge == 0) { attachInterrupt(triggerInterrupt, trigger, RISING); } // Attach the crank trigger wheel interrupt (Hall sensor drags to ground when triggering)
else { attachInterrupt(triggerInterrupt, trigger, FALLING); }
@ -512,6 +542,7 @@ void setup()
trigger = triggerPri_Daihatsu;
getRPM = getRPM_Daihatsu;
getCrankAngle = getCrankAngle_Daihatsu;
triggerSetEndTeeth = triggerSetEndTeeth_Daihatsu;
if(configPage2.TrigEdge == 0) { attachInterrupt(triggerInterrupt, trigger, RISING); } // Attach the crank trigger wheel interrupt (Hall sensor drags to ground when triggering)
else { attachInterrupt(triggerInterrupt, trigger, FALLING); }
@ -845,10 +876,12 @@ void setup()
void loop()
{
mainLoopCount++;
LOOP_TIMER = TIMER_mask;
//Check for any requets from serial. Serial operations are checked under 2 scenarios:
// 1) Every 64 loops (64 Is more than fast enough for TunerStudio). This function is equivalent to ((loopCount % 64) == 1) but is considerably faster due to not using the mod or division operations
// 2) If the amount of data in the serial buffer is greater than a set threhold (See globals.h). This is to avoid serial buffer overflow when large amounts of data is being sent
if ( ((mainLoopCount & 31) == 1) or (Serial.available() > SERIAL_BUFFER_THRESHOLD) )
//if ( ((mainLoopCount & 31) == 1) or (Serial.available() > SERIAL_BUFFER_THRESHOLD) )
if( BIT_CHECK(LOOP_TIMER, BIT_TIMER_15HZ) or (Serial.available() > SERIAL_BUFFER_THRESHOLD) )
{
if (Serial.available() > 0)
{
@ -856,56 +889,28 @@ void loop()
}
}
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) //ATmega2561 does not have Serial3
//if serial3 interface is enabled then check for serial3 requests.
if (configPage10.enable_canbus == 1)
{
if ( ((mainLoopCount & 31) == 1) or (Serial3.available() > SERIAL_BUFFER_THRESHOLD) )
{
if (Serial3.available() > 0)
{
canCommand();
}
}
}
#elif defined(CORE_STM32)
//if can or secondary serial interface is enabled then check for requests.
if (configPage10.enable_canbus == 1) //secondary serial interface enabled
{
if ( ((mainLoopCount & 31) == 1) or (Serial2.available() > SERIAL_BUFFER_THRESHOLD) )
{
if (Serial2.available() > 0)
{
canCommand();
}
}
}
else if (configPage10.enable_canbus == 2) // can module enabled
{
//check local can module
}
#elif defined(CORE_TEENSY)
//if can or secondary serial interface is enabled then check for requests.
if (configPage10.enable_canbus == 1) //secondary serial interface enabled
{
if ( ((mainLoopCount & 31) == 1) or (Serial2.available() > SERIAL_BUFFER_THRESHOLD) )
{
if (Serial2.available() > 0)
{
canCommand();
}
}
}
else if (configPage10.enable_canbus == 2) // can module enabled
{
//check local can module
// if ( ((mainLoopCount & 31) == 1) or (CANbus0.available())
// {
// CANbus0.read(rx_msg);
// }
}
#endif
//if serial3 interface is enabled then check for serial3 requests.
if (configPage10.enable_canbus == 1)
{
//if ( ((mainLoopCount & 31) == 1) or (CANSerial.available() > SERIAL_BUFFER_THRESHOLD) )
if( BIT_CHECK(LOOP_TIMER, BIT_TIMER_15HZ) or (CANSerial.available() > SERIAL_BUFFER_THRESHOLD) )
{
if (CANSerial.available() > 0)
{
canCommand();
}
}
}
#if defined(CORE_TEENSY) || defined(CORE_STM32)
else if (configPage10.enable_canbus == 2) // can module enabled
{
//check local can module
// if ( ((mainLoopCount & 31) == 1) or (CANbus0.available())
// {
// CANbus0.read(rx_msg);
// }
}
#endif
//Displays currently disabled
// if (configPage1.displayType && (mainLoopCount & 255) == 1) { updateDisplay();}
@ -916,7 +921,8 @@ void loop()
if ( (timeToLastTooth < MAX_STALL_TIME) || (toothLastToothTime > currentLoopTime) ) //Check how long ago the last tooth was seen compared to now. If it was more than half a second ago then the engine is probably stopped. toothLastToothTime can be greater than currentLoopTime if a pulse occurs between getting the lastest time and doing the comparison
{
currentStatus.RPM = currentStatus.longRPM = getRPM(); //Long RPM is included here
if(fuelPumpOn == false) { digitalWrite(pinFuelPump, HIGH); fuelPumpOn = true; } //Check if the fuel pump is on and turn it on if it isn't.
//if(fuelPumpOn == false) { digitalWrite(pinFuelPump, HIGH); fuelPumpOn = true; } //Check if the fuel pump is on and turn it on if it isn't.
FUEL_PUMP_ON();
}
else
{
@ -952,8 +958,9 @@ void loop()
//-----------------------------------------------------------------------------------------------------
readMAP();
if ((mainLoopCount & 31) == 1) //Every 32 loops
if (BIT_CHECK(LOOP_TIMER, BIT_TIMER_15HZ)) //Every 32 loops
{
BIT_CLEAR(TIMER_mask, BIT_TIMER_15HZ);
readTPS(); //TPS reading to be performed every 32 loops (any faster and it can upset the TPSdot sampling time)
//Check for launching/flat shift (clutch) can be done around here too
@ -996,14 +1003,19 @@ void loop()
//And check whether the tooth log buffer is ready
if(toothHistoryIndex > TOOTH_LOG_SIZE) { BIT_SET(currentStatus.squirt, BIT_SQUIRT_TOOTHLOG1READY); }
//Most boost tends to run at about 30Hz, so placing it here ensures a new target time is fetched frequently enough
boostControl();
}
if( (mainLoopCount & 63) == 1) //Every 64 loops
if( BIT_CHECK(LOOP_TIMER, BIT_TIMER_30HZ)) //Every 64 loops
{
boostControl(); //Most boost tends to run at about 30Hz, so placing it here ensures a new target time is fetched frequently enough
//Nothing here currently
BIT_CLEAR(TIMER_mask, BIT_TIMER_30HZ);
}
//The IAT and CLT readings can be done less frequently. This still runs about 4 times per second
if ((mainLoopCount & 255) == 1) //Every 256 loops
if (BIT_CHECK(LOOP_TIMER, BIT_TIMER_4HZ)) //Every 256 loops
{
BIT_CLEAR(TIMER_mask, BIT_TIMER_4HZ);
readCLT();
readIAT();
readO2();
@ -1014,15 +1026,15 @@ void loop()
{
if (configPage10.enable_candata_in)
{
if (configPage10.caninput_sel[currentStatus.current_caninchannel]) //if current input channel is enabled
if (BIT_CHECK(configPage10.caninput_sel,currentStatus.current_caninchannel)) //if current input channel bit is enabled
{
sendCancommand(2,0,0,0,configPage10.caninput_param_group[currentStatus.current_caninchannel]); //send an R command for data from paramgroup[currentStatus.current_caninchannel]
sendCancommand(2,0,currentStatus.current_caninchannel,0,((configPage10.caninput_param_group[currentStatus.current_caninchannel]&2047)+256)); //send an R command for data from paramgroup[currentStatus.current_caninchannel]
}
else
{
if (currentStatus.current_caninchannel <= 6)
if (currentStatus.current_caninchannel < 15)
{
currentStatus.current_caninchannel++; //step to next input channel if under 9
currentStatus.current_caninchannel++; //step to next input channel if under 15
}
else
{
@ -1035,26 +1047,26 @@ void loop()
//if serial3io is enabled then check for serial3 requests.
if (configPage10.enable_candata_in)
{
if (configPage10.caninput_sel[currentStatus.current_caninchannel]) //if current input channel is enabled
if (BIT_CHECK(configPage10.caninput_sel,currentStatus.current_caninchannel)) //if current input channel is enabled
{
if (configPage10.enable_canbus == 1) //can via secondary serial
{
sendCancommand(2,0,0,0,configPage10.caninput_param_group[currentStatus.current_caninchannel]); //send an R command for data from paramgroup[currentStatus.current_caninchannel]
sendCancommand(2,0,currentStatus.current_caninchannel,0,((configPage10.caninput_param_group[currentStatus.current_caninchannel]&2047)+256)); //send an R command for data from paramgroup[currentStatus.current_caninchannel]
}
else if (configPage10.enable_canbus == 2) // can via internal can module
{
sendCancommand(3,configPage10.speeduino_tsCanId,0,0,configPage10.caninput_param_group[currentStatus.current_caninchannel]); //send via localcanbus the command for data from paramgroup[currentStatus.current_caninchannel]
sendCancommand(3,configPage10.speeduino_tsCanId,currentStatus.current_caninchannel,0,configPage10.caninput_param_group[currentStatus.current_caninchannel]); //send via localcanbus the command for data from paramgroup[currentStatus.current_caninchannel]
}
}
else
{
if (currentStatus.current_caninchannel <= 6)
if (currentStatus.current_caninchannel < 15)
{
currentStatus.current_caninchannel++; //step to next input channel if under 9
currentStatus.current_caninchannel++; //step to next input channel if under 15
}
else
{
currentStatus.current_caninchannel = 0; //reset input channel back to 1
currentStatus.current_caninchannel = 0; //reset input channel back to 0
}
}
}
@ -1063,6 +1075,13 @@ void loop()
vvtControl();
idleControl(); //Perform any idle related actions. Even at higher frequencies, running 4x per second is sufficient.
}
if (BIT_CHECK(LOOP_TIMER, BIT_TIMER_1HZ)) //Every 1024 loops (Approx. 1 per second)
{
//Approx. once per second
readBaro();
BIT_CLEAR(TIMER_mask, BIT_TIMER_1HZ);
}
if(configPage4.iacAlgorithm == IAC_ALGORITHM_STEP_OL || configPage4.iacAlgorithm == IAC_ALGORITHM_STEP_CL) { idleControl(); } //Run idlecontrol every loop for stepper idle.
//Always check for sync
@ -1070,6 +1089,7 @@ void loop()
if (currentStatus.hasSync && (currentStatus.RPM > 0))
{
if(currentStatus.startRevolutions >= configPage2.StgCycles) { ignitionOn = true; fuelOn = true;} //Enable the fuel and ignition, assuming staging revolutions are complete
else { ignitionOn = false; fuelOn = false;}
//If it is, check is we're running or cranking
if(currentStatus.RPM > ((unsigned int)configPage2.crankRPM * 100)) //Crank RPM stored in byte as RPM / 100
{
@ -1094,7 +1114,7 @@ void loop()
//Begin the fuel calculation
//Calculate an injector pulsewidth from the VE
currentStatus.corrections = correctionsFuel();
//currentStatus.corrections = 100;
lastAdvance = currentStatus.advance; //Store the previous advance value
if (configPage1.algorithm == 0) //Check which fuelling algorithm is being used
{
//Speed Density
@ -1280,7 +1300,8 @@ void loop()
//Calculate start angle for each channel
//1 cylinder (Everyone gets this)
ignition1StartAngle = CRANK_ANGLE_MAX_IGN - currentStatus.advance - dwellAngle; // 360 - desired advance angle - number of degrees the dwell will take
ignition1EndAngle = CRANK_ANGLE_MAX_IGN - currentStatus.advance;
ignition1StartAngle = ignition1EndAngle - dwellAngle; // 360 - desired advance angle - number of degrees the dwell will take
if(ignition1StartAngle < 0) {ignition1StartAngle += CRANK_ANGLE_MAX_IGN;}
//This test for more cylinders and do the same thing
@ -1288,40 +1309,50 @@ void loop()
{
//2 cylinders
case 2:
ignition2StartAngle = channel2IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance - dwellAngle;
ignition2EndAngle = channel2IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance;
ignition2StartAngle = ignition2EndAngle - dwellAngle;
if(ignition2StartAngle > CRANK_ANGLE_MAX_IGN) {ignition2StartAngle -= CRANK_ANGLE_MAX_IGN;}
break;
//3 cylinders
case 3:
ignition2StartAngle = channel2IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance - dwellAngle;
ignition2EndAngle = channel2IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance;
ignition2StartAngle = ignition2EndAngle - dwellAngle;
if(ignition2StartAngle > CRANK_ANGLE_MAX_IGN) {ignition2StartAngle -= CRANK_ANGLE_MAX_IGN;}
ignition3EndAngle = channel3IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance;
ignition3StartAngle = channel3IgnDegrees + 360 - currentStatus.advance - dwellAngle;
if(ignition3StartAngle > CRANK_ANGLE_MAX_IGN) {ignition3StartAngle -= CRANK_ANGLE_MAX_IGN;}
break;
//4 cylinders
case 4:
ignition2StartAngle = channel2IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance - dwellAngle;
ignition2EndAngle = channel2IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance;
ignition2StartAngle = ignition2EndAngle - dwellAngle;
if(ignition2StartAngle > CRANK_ANGLE_MAX_IGN) {ignition2StartAngle -= CRANK_ANGLE_MAX_IGN;}
if(ignition2StartAngle < 0) {ignition2StartAngle += CRANK_ANGLE_MAX_IGN;}
if(configPage2.sparkMode == IGN_MODE_SEQUENTIAL)
{
ignition3StartAngle = channel3IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance - dwellAngle;
ignition3EndAngle = channel3IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance;
ignition3StartAngle = ignition3EndAngle - dwellAngle;
if(ignition3StartAngle > CRANK_ANGLE_MAX_IGN) {ignition3StartAngle -= CRANK_ANGLE_MAX_IGN;}
ignition4StartAngle = channel4IgnDegrees + CRANK_ANGLE_MAX - currentStatus.advance - dwellAngle;
ignition4EndAngle = channel4IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance;
ignition4StartAngle = ignition4EndAngle - dwellAngle;
if(ignition4StartAngle > CRANK_ANGLE_MAX_IGN) {ignition4StartAngle -= CRANK_ANGLE_MAX_IGN;}
}
break;
//5 cylinders
case 5:
ignition2StartAngle = channel2IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance - dwellAngle;
ignition2EndAngle = channel2IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance;
ignition2StartAngle = ignition2EndAngle - dwellAngle;
if(ignition2StartAngle > CRANK_ANGLE_MAX_IGN) {ignition2StartAngle -= CRANK_ANGLE_MAX_IGN;}
if(ignition2StartAngle < 0) {ignition2StartAngle += CRANK_ANGLE_MAX_IGN;}
ignition3StartAngle = channel3IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance - dwellAngle;
ignition3EndAngle = channel3IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance;
ignition3StartAngle = ignition3EndAngle - dwellAngle;
if(ignition3StartAngle > CRANK_ANGLE_MAX_IGN) {ignition3StartAngle -= CRANK_ANGLE_MAX_IGN;}
ignition4StartAngle = channel4IgnDegrees + CRANK_ANGLE_MAX - currentStatus.advance - dwellAngle;
ignition4EndAngle = channel4IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance;
ignition4StartAngle = ignition4EndAngle - dwellAngle;
if(ignition4StartAngle > CRANK_ANGLE_MAX_IGN) {ignition4StartAngle -= CRANK_ANGLE_MAX_IGN;}
ignition5StartAngle = channel5IgnDegrees + CRANK_ANGLE_MAX - currentStatus.advance - dwellAngle;
@ -1330,18 +1361,26 @@ void loop()
break;
//6 cylinders
case 6:
ignition2StartAngle = channel2IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance - dwellAngle;
ignition2EndAngle = channel2IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance;
ignition2StartAngle = ignition2EndAngle - dwellAngle;
if(ignition2StartAngle > CRANK_ANGLE_MAX_IGN) {ignition2StartAngle -= CRANK_ANGLE_MAX_IGN;}
ignition3StartAngle = channel3IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance - dwellAngle;
ignition3EndAngle = channel3IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance;
ignition3StartAngle = ignition3EndAngle - dwellAngle;
if(ignition3StartAngle > CRANK_ANGLE_MAX_IGN) {ignition3StartAngle -= CRANK_ANGLE_MAX_IGN;}
break;
//8 cylinders
case 8:
ignition2StartAngle = channel2IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance - dwellAngle;
ignition2EndAngle = channel2IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance;
ignition2StartAngle = ignition2EndAngle - dwellAngle;
if(ignition2StartAngle > CRANK_ANGLE_MAX_IGN) {ignition2StartAngle -= CRANK_ANGLE_MAX_IGN;}
ignition3StartAngle = channel3IgnDegrees + CRANK_ANGLE_MAX - currentStatus.advance - dwellAngle;
ignition3EndAngle = channel3IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance;
ignition3StartAngle = ignition3EndAngle - dwellAngle;
if(ignition3StartAngle > CRANK_ANGLE_MAX_IGN) {ignition3StartAngle -= CRANK_ANGLE_MAX_IGN;}
ignition4StartAngle = channel4IgnDegrees + CRANK_ANGLE_MAX - currentStatus.advance - dwellAngle;
ignition4EndAngle = channel4IgnDegrees + CRANK_ANGLE_MAX_IGN - currentStatus.advance;
ignition4StartAngle = ignition4EndAngle - dwellAngle;
if(ignition4StartAngle > CRANK_ANGLE_MAX_IGN) {ignition4StartAngle -= CRANK_ANGLE_MAX_IGN;}
break;
@ -1349,6 +1388,9 @@ void loop()
default:
break;
}
//If ignition timing is being tracked per tooth, perform the calcs to get the end teeth
//This only needs to be run if the advance figure has changed, otherwise the end teeth will still be the same
if( (configPage1.perToothIgn == true) && (lastAdvance != currentStatus.advance) ) { triggerSetEndTeeth(); }
//***********************************************************************************************
//| BEGIN FUEL SCHEDULES

View File

@ -48,7 +48,8 @@ Current layout of EEPROM data (Version 3) is as follows (All sizes are in bytes)
| 1441 |2 | X and Y size4 |
| 1443 |36 | PAGE 9 MAP4 |
| 1479 |6 | X and Y Bins4 |
| 1500 |128 | CANBUS config and data |
| 1500 |128 | CANBUS config and data (Table 10_) |
| 1628 |192 | Table 11 - General settings |
| |
| 2559 |512 | Calibration data (O2) |
| 3071 |512 | Calibration data (IAT) |
@ -115,6 +116,8 @@ Current layout of EEPROM data (Version 3) is as follows (All sizes are in bytes)
#define EEPROM_CONFIG9_YBINS4 1485
#define EEPROM_CONFIG10_START 1500
#define EEPROM_CONFIG10_END 1628
#define EEPROM_CONFIG11_START 1628
#define EEPROM_CONFIG11_END 1820
//Calibration data is stored at the end of the EEPROM (This is in case any further calibration tables are needed as they are large blocks)
#define EEPROM_LAST_BARO 2558
@ -122,4 +125,4 @@ Current layout of EEPROM data (Version 3) is as follows (All sizes are in bytes)
#define EEPROM_CALIBRATION_IAT 3071
#define EEPROM_CALIBRATION_CLT 3583
#endif // STORAGE_H
#endif // STORAGE_H

View File

@ -271,8 +271,19 @@ void writeConfig()
{
if(EEPROM.read(x) != *(pnt_configPage + byte(x - EEPROM_CONFIG10_START))) { EEPROM.write(x, *(pnt_configPage + byte(x - EEPROM_CONFIG10_START))); }
}
//*********************************************************************************************************************************************************************************
//*********************************************************************************************************************************************************************************
/*---------------------------------------------------
| Config page 11 (See storage.h for data layout)
| 192 byte long config table
-----------------------------------------------------*/
pnt_configPage = (byte *)&configPage11; //Create a pointer to Page 11 in memory
//As there are no 3d tables in this page, all 192 bytes can simply be read in
for(int x=EEPROM_CONFIG11_START; x<EEPROM_CONFIG11_END; x++)
{
if(EEPROM.read(x) != *(pnt_configPage + byte(x - EEPROM_CONFIG11_START))) { EEPROM.write(x, *(pnt_configPage + byte(x - EEPROM_CONFIG11_START))); }
}
}
void loadConfig()
@ -476,6 +487,14 @@ void loadConfig()
//*********************************************************************************************************************************************************************************
//CONFIG PAGE (11)
pnt_configPage = (byte *)&configPage11; //Create a pointer to Page 11 in memory
//All 192 bytes can simply be pulled straight from the configTable
for(int x=EEPROM_CONFIG11_START; x<EEPROM_CONFIG11_END; x++)
{
*(pnt_configPage + byte(x - EEPROM_CONFIG11_START)) = EEPROM.read(x);
}
}
/*
@ -519,5 +538,3 @@ void writeCalibration()
}
}

View File

@ -23,7 +23,8 @@ struct table2D {
int *axisX16;
//Store the last X and Y coordinates in the table. This is used to make the next check faster
int lastXMax, lastXMin;
int lastXMax;
int lastXMin;
};
void table2D_setSize(struct table2D targetTable, byte newSize);

View File

@ -103,6 +103,7 @@ int table2D_getValue(struct table2D *fromTable, int X_in)
{
returnValue = fromTable->values[x]; //Simply return the coresponding value
valueFound = true;
break;
}
else
{
@ -143,6 +144,7 @@ int table2D_getValue(struct table2D *fromTable, int X_in)
{
returnValue = fromTable->values16[x]; //Simply return the coresponding value
valueFound = true;
break;
}
else
{
@ -366,7 +368,7 @@ int get3DTableValue(struct table3D *fromTable, int Y_in, int X_in)
int D = fromTable->values[yMax][xMax];
//Check that all values aren't just the same (This regularly happens with things like the fuel trim maps)
if( (A == D) ) { tableResult = A; }
if( (A == B) && (A == C) && (A == D) ) { tableResult = A; }
else
{
//Create some normalised position values
@ -374,13 +376,29 @@ int get3DTableValue(struct table3D *fromTable, int Y_in, int X_in)
//Initial check incase the values were hit straight on
long p = (long)X - xMinValue;
if (xMaxValue == xMinValue) { p = (p << 8); } //This only occurs if the requested X value was equal to one of the X axis bins
else { p = ( (p << 8) / (xMaxValue - xMinValue) ); } //This is the standard case
long q = (long)Y - yMinValue;
if (yMaxValue == yMinValue) { q = (q << 8); }
else { q = 256 - ( (q << 8) / (yMinValue - yMaxValue) ); }
long q;
if (yMaxValue == yMinValue)
{
q = (long)Y - yMinValue;
q = (q << 8);
}
//Standard case
else
{
q = long(Y) - yMaxValue;
q = 256 - ( (q << 8) / (yMinValue - yMaxValue) );
}
/*
long q;
if (yMaxValue == yMinValue) { q = ((long)(Y - yMinValue) << 8); }
else { q = 256 - (((long)(Y - yMaxValue) << 8) / (yMinValue - yMaxValue)); }
*/
int m = ((256-p) * (256-q)) >> 8;
int n = (p * (256-q)) >> 8;
@ -390,91 +408,87 @@ int get3DTableValue(struct table3D *fromTable, int Y_in, int X_in)
}
return tableResult;
}
/* Executed a benchmark on all options and this is the results
* @Mega: Stadard:463028 92 |FP Math:850392 92.57 |Clean code:618308 92 , Number of loops:5000
* @STM32F1: Stadard:21449 92 |FP Math:125707 92.57 |Clean code:11634 92 , Number of loops:5000
* @STM32F4: Stadard:7123 92 |FP Math:16503 92.57 |Clean code:4618 92 , Number of loops:5000
* @STM32F1: Stadard:13000 loops/S |Clean code:15700 loops/S @8000RPM ~20.8% faster
* Stadard:226224 91 |FP Math:32240 91.89 |Clean code:34056 91, Number of loops:2500
*
//This function pulls a value from a 3D table given a target for X and Y coordinates.
//It performs a 2D linear interpolation as descibred in: http://www.megamanual.com/v22manual/ve_tuner.pdf
float get3DTableValueF(struct table3D *fromTable, int Y, int X)
{
float m, n, o ,p, q, r;
byte xMin, xMax;
byte yMin, yMax;
int yMaxValue, yMinValue;
int xMaxValue, xMinValue;
float tableResult = 0;
xMin = fromTable->lastXMin;
yMin = fromTable->lastYMin;
if(xMin == 0) { xMin = fromTable->xSize-1; }
if(yMin == 0) { yMin = fromTable->ySize-1; }
if(fromTable->lastXMin==0) {fromTable->lastXMin = fromTable->xSize-1;}
else {xMin = fromTable->lastXMin;}
if(fromTable->lastYMin==0) {fromTable->lastYMin = fromTable->ySize-1;}
else {yMin = fromTable->lastYMin;}
//yMin = fromTable->lastYMin;
if(xMin>fromTable->xSize-1)
{
fromTable->lastXMin = fromTable->xSize-1;
xMin = fromTable->xSize-1;
}
if(yMin>fromTable->ySize-1)
{
fromTable->lastYMin = fromTable->ySize-1;
yMin = fromTable->ySize-1;
}
do //RPM axis
{
if(X >= fromTable->axisX[xMin]) {break;}
if(X>=fromTable->axisX[xMin]) {break;}
xMin--;
}while(1);
fromTable->lastXMin = xMin + 1;
do //MAP axis
{
if(Y <= fromTable->axisY[yMin]) {break;}
if(Y<=fromTable->axisY[yMin]) {break;}
yMin--;
}while(1);
fromTable->lastYMin = yMin + 1;
xMax = xMin + 1;
yMax = yMin + 1;
if (xMax > fromTable->xSize-1) //Overflow protection
if (xMax>fromTable->xSize-1) //Overflow protection
{
xMax = fromTable->xSize-1;
xMin = xMax - 1;
}
fromTable->lastXMin = xMin + 1;
if (yMax > fromTable->ySize-1) //Overflow protection
if (yMax>fromTable->ySize-1) //Overflow protection
{
yMax = fromTable->ySize-1;
yMin = yMax - 1;
}
fromTable->lastYMin = yMin + 1;
yMaxValue = fromTable->axisY[yMax];
yMinValue = fromTable->axisY[yMin];
xMaxValue = fromTable->axisX[xMax];
xMinValue = fromTable->axisX[xMin];
int A = fromTable->values[yMin][xMin];
int B = fromTable->values[yMin][xMax];
int C = fromTable->values[yMax][xMin];
int D = fromTable->values[yMax][xMax];
if(A == D) { tableResult = A; }
else
{
int B = fromTable->values[yMin][xMax];
int C = fromTable->values[yMax][xMin];
yMaxValue = fromTable->axisY[yMax];
yMinValue = fromTable->axisY[yMin];
xMaxValue = fromTable->axisX[xMax];
xMinValue = fromTable->axisX[xMin];
float m, n, o ,p, q, r;
p = float(X - xMinValue) / (xMaxValue - xMinValue); //(RPM - RPM[1])/(RPM[2]- RPM[1])
q = float(Y - yMinValue) / (yMaxValue - yMinValue); //(MAP - MAP[1])/(MAP[2]- MAP[1])
p = float(X - xMinValue) / (xMaxValue - xMinValue); //(RPM - RPM[1])/(RPM[2]- RPM[1])
q = float(Y - yMinValue) / (yMaxValue - yMinValue); //(MAP - MAP[1])/(MAP[2]- MAP[1])
m = (1.0-p) * (1.0-q);
n = p * (1-q);
o = (1-p) * q;
r = p * q;
tableResult = ( (A * m) + (B * n) + (C * o) + (D * r) );
}
return tableResult;
m = (1.0-p) * (1.0-q);
n = p * (1-q);
o = (1-p) * q;
r = p * q;
return ( (A * m) + (B * n) + (C * o) + (D * r) );
}
//This function pulls a value from a 3D table given a target for X and Y coordinates.
//It performs a 2D linear interpolation as descibred in: http://www.megamanual.com/v22manual/ve_tuner.pdf
*/
int get3DTableValueS(struct table3D *fromTable, int Y, int X)
{
byte xMin, xMax;
byte yMin, yMax;
long p, q;
int yMaxValue, yMinValue;
int xMaxValue, xMinValue;
int tableResult = 0;
xMin = fromTable->lastXMin;
@ -484,54 +498,94 @@ int get3DTableValueS(struct table3D *fromTable, int Y, int X)
do //RPM axis
{
if(X >= fromTable->axisX[xMin]) {break;}
if(X > fromTable->axisX[xMin])
{
if (xMin == (fromTable->xSize-1) ) { xMax = xMin; } //Overflow protection
else { xMax = xMin + 1; }
break;
}
else if(X == fromTable->axisX[xMin])
{
xMax = xMin;
break;
}
xMin--;
}while(1);
}while(true);
do //MAP axis
{
if(Y <= fromTable->axisY[yMin]) {break;}
if(Y < fromTable->axisY[yMin])
{
if (yMin == (fromTable->ySize-1) ) { yMax = yMin; } //Overflow protection
else { yMax = yMin + 1; }
break;
}
else if(Y == fromTable->axisY[yMin])
{
yMax = yMin;
break;
}
yMin--;
}while(1);
xMax = xMin + 1;
yMax = yMin + 1;
if (xMax > fromTable->xSize-1) //Overflow protection
{
xMax = fromTable->xSize-1;
xMin = xMax - 1;
}
fromTable->lastXMin = xMin + 1;
}while(true);
if (yMax > fromTable->ySize-1) //Overflow protection
{
yMax = fromTable->ySize-1;
yMin = yMax - 1;
}
fromTable->lastYMin = yMin + 1;
fromTable->lastXMin = xMax;
fromTable->lastYMin = yMax;
//Serial.print("xMin, xMax ");Serial.print(xMin);Serial.print(",");Serial.println(xMax);
//Serial.print("yMin, yMax ");Serial.print(yMin);Serial.print(",");Serial.println(yMax);
int A = fromTable->values[yMin][xMin];
int D = fromTable->values[yMax][xMax];
if(A == D) { tableResult = A; }
if((xMin == xMax) && (yMin == yMax)) { tableResult = A; }
else if(xMin == xMax) // Simple 2D
{
int D = fromTable->values[yMax][xMax];
int yMaxValue = fromTable->axisY[yMax];
int yMinValue = fromTable->axisY[yMin];
long q = (long)Y - yMinValue;
q = ((q << 6) * (D - A)) / (yMaxValue - yMinValue);
tableResult = A + (q >> 6);
}
else if(yMin == yMax) // Simple 2D
{
int D = fromTable->values[yMax][xMax];
int xMaxValue = fromTable->axisX[xMax];
int xMinValue = fromTable->axisX[xMin];
long q = (long)X - xMinValue;
q = ((q << 6) * (D - A)) / (xMaxValue - xMinValue);
tableResult = A + (q >> 6);
}
else
{
int B = fromTable->values[yMin][xMax];
int C = fromTable->values[yMax][xMin];
int D = fromTable->values[yMax][xMax];
yMaxValue = fromTable->axisY[yMax];
yMinValue = fromTable->axisY[yMin];
xMaxValue = fromTable->axisX[xMax];
xMinValue = fromTable->axisX[xMin];
int yMaxValue = fromTable->axisY[yMax];
int yMinValue = fromTable->axisY[yMin];
int xMaxValue = fromTable->axisX[xMax];
int xMinValue = fromTable->axisX[xMin];
p = ((long)(X - xMinValue) << 8) / (xMaxValue - xMinValue); //(RPM - RPM[1])/(RPM[2]- RPM[1])
q = 256 - (((long)(Y - yMaxValue) << 8) / (yMinValue - yMaxValue)); //(MAP - MAP[2])/(MAP[2]- MAP[1])
long p = (long)X - xMinValue;
if (xMaxValue == xMinValue) { p = (p << 8); } //This only occurs if the requested X value was equal to one of the X axis bins
else { p = ( (p << 8) / (xMaxValue - xMinValue) ); } //This is the standard case
long q;
if (yMaxValue == yMinValue)
{
q = (long)Y - yMinValue;
q = (q << 8);
}
else
{
q = long(Y) - yMaxValue;
q = 256 - ( (q << 8) / (yMinValue - yMaxValue) );
}
int m = ((256-p) * (256-q)) >> 8;
int n = (p * (256-q)) >> 8;
int o = ((256-p) * q) >> 8;
int r = (p * q) >> 8;
tableResult = ( (A * m) + (B * n) + (C * o) + (D * r) ) >> 8;
tableResult = ( (A * m) + (B * n) + (C * o) + (D * r) ) >> 8;
}
return tableResult;
return tableResult;
}
*/

View File

@ -19,8 +19,10 @@ Hence we will preload the timer with 131 cycles to leave 125 until overflow (1ms
#ifndef TIMERS_H
#define TIMERS_H
volatile int loop100ms;
volatile int loop250ms;
volatile byte loop33ms;
volatile byte loop66ms;
volatile byte loop100ms;
volatile byte loop250ms;
volatile int loopSec;
volatile unsigned int dwellLimit_uS;

View File

@ -44,9 +44,10 @@ void initialiseTimers()
// Set up an interrupt
Timer4.setMode(1, TIMER_OUTPUT_COMPARE);
Timer4.attachInterrupt(1, oneMSInterval);
Timer4.resume();
Timer4.resume(); //Start Timer
#endif
pinMode(LED_BUILTIN, OUTPUT); //pinMode(13, OUTPUT);
dwellLimit_uS = (1000 * configPage2.dwellLimit);
lastRPM_100ms = 0;
}
@ -62,6 +63,8 @@ void oneMSInterval() //Most ARM chips can simply call a function
{
//Increment Loop Counters
loop33ms++;
loop66ms++;
loop100ms++;
loop250ms++;
loopSec++;
@ -78,11 +81,27 @@ void oneMSInterval() //Most ARM chips can simply call a function
if(ignitionSchedule4.Status == RUNNING) { if( (ignitionSchedule4.startTime < targetOverdwellTime) && (configPage2.useDwellLim) ) { endCoil4Charge(); } }
if(ignitionSchedule5.Status == RUNNING) { if( (ignitionSchedule5.startTime < targetOverdwellTime) && (configPage2.useDwellLim) ) { endCoil5Charge(); } }
//15Hz loop
if (loop66ms == 66)
{
loop66ms = 0;
BIT_SET(TIMER_mask, BIT_TIMER_15HZ);
}
//30Hz loop
if (loop33ms == 33)
{
loop33ms = 0;
BIT_SET(TIMER_mask, BIT_TIMER_30HZ);
}
//Loop executed every 100ms loop
//Anything inside this if statement will run every 100ms.
if (loop100ms == 100)
{
loop100ms = 0; //Reset counter
BIT_SET(TIMER_mask, BIT_TIMER_10HZ);
digitalWrite(LED_BUILTIN, !digitalRead(LED_BUILTIN));
currentStatus.rpmDOT = (currentStatus.RPM - lastRPM_100ms) * 10; //This is the RPM per second that the engine has accelerated/decelleratedin the last loop
lastRPM_100ms = currentStatus.RPM; //Record the current RPM for next calc
@ -93,6 +112,7 @@ void oneMSInterval() //Most ARM chips can simply call a function
if (loop250ms == 250)
{
loop250ms = 0; //Reset Counter.
BIT_SET(TIMER_mask, BIT_TIMER_4HZ);
#if defined(CORE_AVR)
//Reset watchdog timer (Not active currently)
//wdt_reset();
@ -103,7 +123,7 @@ void oneMSInterval() //Most ARM chips can simply call a function
if (loopSec == 1000)
{
loopSec = 0; //Reset counter.
BIT_SET(TIMER_mask, BIT_TIMER_1HZ);
dwellLimit_uS = (1000 * configPage2.dwellLimit); //Update uS value incase setting has changed
if ( configPage2.ignCranklock && BIT_CHECK(currentStatus.engine, BIT_ENGINE_CRANK)) { dwellLimit_uS = dwellLimit_uS * 3; } //Make sure the overdwell doesn't clobber the fixed ignition cranking if enabled.

View File

@ -8,7 +8,7 @@
void doUpdates()
{
#define CURRENT_DATA_VERSION 3
#define CURRENT_DATA_VERSION 4
//May 2017 firmware introduced a -40 offset on the ignition table. Update that table to +40
if(EEPROM.read(EEPROM_DATA_VERSION) == 2)
@ -23,6 +23,19 @@ void doUpdates()
writeConfig();
EEPROM.write(EEPROM_DATA_VERSION, 3);
}
//June 2017 required the forced addition of some CAN values to avoid weird errors
if(EEPROM.read(EEPROM_DATA_VERSION) == 3)
{
configPage10.speeduino_tsCanId = 0;
configPage10.true_address = 256;
configPage10.realtime_base_address = 336;
//There was a bad value in the May base tune for the spark duration setting, fix it here if it's a problem
if(configPage2.sparkDur == 255) { configPage2.sparkDur = 10; }
writeConfig();
EEPROM.write(EEPROM_DATA_VERSION, 4);
}
//Final check is always for 255 and 0 (Brand new arduino)
if( (EEPROM.read(EEPROM_DATA_VERSION) == 0) || (EEPROM.read(EEPROM_DATA_VERSION) == 255) )

View File

@ -1,15 +1,55 @@
/*
These are some utility functions and variables used through the main code
*/
*/
#ifndef UTILS_H
#define UTILS_H
#include <Arduino.h>
unsigned int freeRam ();
uint16_t freeRam ();
void setPinMapping(byte boardID);
unsigned int PW();
unsigned int PW_SD();
unsigned int PW_AN();
#if defined(CORE_STM32)
//STM32F1/variants/.../board.cpp
#if defined (STM32F4)
#define A0 PA0
#define A1 PA1
#define A2 PA2
#define A3 PA3
#define A4 PA4
#define A5 PA5
#define A6 PA6
#define A7 PA7
#define A8 PB0
#define A9 PB1
#define A10 PC0
#define A11 PC1
#define A12 PC2
#define A13 PC3
#define A14 PC4
#define A15 PC5
#else
#define A0 PB0
#define A1 PA7
#define A2 PA6
#define A3 PA5
#define A4 PA4
#define A5 PA3
#define A6 PA2
#define A7 PA1
#define A8 PA0
//STM32F1 have only 9 12bit adc
#define A9 PB0
#define A10 PA7
#define A11 PA6
#define A12 PA5
#define A13 PA4
#define A14 PA3
#define A15 PA2
#endif
#endif
#endif // UTILS_H

View File

@ -7,15 +7,18 @@
/*
Returns how much free dynamic memory exists (between heap and stack)
This function is one big MISRA violation. MISRA advisories forbid directly poking at memory addresses, however there is no other way of determining heap size on embedded systems.
*/
#include "utils.h"
unsigned int freeRam ()
uint16_t freeRam ()
{
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
extern int __heap_start, *__brkval;
int v;
return (int) &v - (__brkval == 0 ? (int) &__heap_start : (int) __brkval);
uint16_t v;
return (uint16_t) &v - (__brkval == 0 ? (int) &__heap_start : (int) __brkval);
#elif defined(CORE_TEENSY)
uint32_t stackTop;
uint32_t heapTop;
@ -33,52 +36,13 @@ unsigned int freeRam ()
#elif defined(CORE_STM32)
char top = 't';
return &top - reinterpret_cast<char*>(sbrk(0));
#endif
}
void setPinMapping(byte boardID)
{
//This is dumb, but it'll do for now to get things compiling
#if defined(CORE_STM32)
//STM32F1/variants/.../board.cpp
#if defined (STM32F4)
#define A0 PA0
#define A1 PA1
#define A2 PA2
#define A3 PA3
#define A4 PA4
#define A5 PA5
#define A6 PA6
#define A7 PA7
#define A8 PB0
#define A9 PB1
#define A10 PC0
#define A11 PC1
#define A12 PC2
#define A13 PC3
#define A14 PC4
#define A15 PC5
#else
#define A0 PB0
#define A1 PA7
#define A2 PA6
#define A3 PA5
#define A4 PA4
#define A5 PA3
#define A6 PA2
#define A7 PA1
#define A8 PA0
//STM32F1 have only 9 12bit adc
#define A9 PB0
#define A10 PA7
#define A11 PA6
#define A12 PA5
#define A13 PA4
#define A14 PA3
#define A15 PA2
#endif
#endif
switch (boardID)
{
case 0:
@ -183,35 +147,6 @@ 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;
@ -271,12 +206,13 @@ void setPinMapping(byte boardID)
pinCoil3 = PB12; //Pin for coil 3
pinCoil4 = PB13; //Pin for coil 4
pinCoil5 = PB14; //Pin for coil 5
pinTPS = PA0; //TPS input pin
pinMAP = PA1; //MAP sensor pin
pinIAT = PA2; //IAT sensor pin
pinCLT = PA3; //CLS sensor pin
pinO2 = PA4; //O2 Sensor pin
pinBat = PA5; //Battery reference voltage 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
pinBat = A5; //Battery reference voltage pin
pinBaro = A6;
pinStepperDir = PD8; //Direction pin for DRV8825 driver
pinStepperStep = PB15; //Step pin for DRV8825 driver
pinStepperEnable = PD9; //Enable pin for DRV8825
@ -317,6 +253,7 @@ void setPinMapping(byte boardID)
pinFlex = 32; // Flex sensor (Must be external interrupt enabled)
pinTrigger = 25; //The CAS pin
pinTrigger2 = 22; //The Cam Sensor pin
pinBaro = pinMAP;
#endif
break;
@ -324,8 +261,8 @@ void setPinMapping(byte boardID)
//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
pinInjector3 = 8; //Output pin injector 3 is on
pinInjector4 = 9; //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
@ -417,6 +354,7 @@ void setPinMapping(byte boardID)
pinFan = 47; //Pin for the fan output
pinFuelPump = 4; //Fuel pump output
pinTachOut = 49; //Tacho output pin
break;
case 30:
//Pin mappings as per the dazv6 shield
@ -486,18 +424,15 @@ void setPinMapping(byte boardID)
break;
}
//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; }
}
//Setup any devices that are using selectable pins
if ( (configPage3.launchPin != 0) && (configPage3.launchPin < BOARD_NR_GPIO_PINS) ) { pinLaunch = configPage3.launchPin; }
if ( (configPage2.ignBypassPin != 0) && (configPage2.ignBypassPin < BOARD_NR_GPIO_PINS) ) { pinIgnBypass = configPage2.ignBypassPin; }
if ( (configPage1.tachoPin != 0) && (configPage1.tachoPin < BOARD_NR_GPIO_PINS) ) { pinTachOut = configPage1.tachoPin; }
if ( (configPage2.fuelPumpPin != 0) && (configPage2.fuelPumpPin < BOARD_NR_GPIO_PINS) ) { pinFuelPump = configPage2.fuelPumpPin; }
if ( (configPage4.fanPin != 0) && (configPage4.fanPin < BOARD_NR_GPIO_PINS) ) { pinFan = configPage4.fanPin; }
if ( (configPage3.boostPin != 0) && (configPage3.boostPin < BOARD_NR_GPIO_PINS) ) { pinBoost = configPage3.boostPin; }
if ( (configPage3.vvtPin != 0) && (configPage3.vvtPin < BOARD_NR_GPIO_PINS) ) { pinVVT_1 = configPage3.vvtPin; }
if ( (configPage3.useExtBaro != 0) && (configPage3.baroPin < BOARD_NR_GPIO_PINS) ) { pinBaro = configPage3.baroPin + A0; }
//Finally, set the relevant pin modes for outputs
pinMode(pinCoil1, OUTPUT);
@ -546,6 +481,8 @@ void setPinMapping(byte boardID)
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);
@ -555,12 +492,12 @@ void setPinMapping(byte boardID)
pinMode(pinIAT, INPUT);
pinMode(pinCLT, INPUT);
pinMode(pinBat, INPUT);
pinMode(pinBaro, INPUT);
pinMode(pinTrigger, INPUT);
pinMode(pinTrigger2, INPUT);
pinMode(pinTrigger3, INPUT);
pinMode(pinFlex, INPUT_PULLUP); //Standard GM / Continental flex sensor requires pullup
// pinMode(pinLaunch, INPUT_PULLUP); //This should work for both NO and NC grounding switches
if (configPage3.lnchPullRes) {
if (configPage3.lnchPullRes == true) {
pinMode(pinLaunch, INPUT_PULLUP);
}
else {
@ -598,34 +535,37 @@ unsigned int PW(int REQ_FUEL, byte VE, byte MAP, int corrections, int injOpen)
//Standard float version of the calculation
//return (REQ_FUEL * (float)(VE/100.0) * (float)(MAP/100.0) * (float)(TPS/100.0) * (float)(corrections/100.0) + injOpen);
//Note: The MAP and TPS portions are currently disabled, we use VE and corrections only
unsigned int iVE, iMAP, iAFR, iCorrections;
uint16_t iVE, iCorrections;
uint16_t iMAP = 100;
uint16_t iAFR = 147;
//100% float free version, does sacrifice a little bit of accuracy, but not much.
iVE = ((unsigned int)VE << 7) / 100;
if ( configPage1.multiplyMAP ) {
if ( configPage1.multiplyMAP == true ) {
iMAP = ((unsigned int)MAP << 7) / currentStatus.baro; //Include multiply MAP (vs baro) if enabled
}
if ( configPage1.includeAFR && (configPage3.egoType == 2)) {
if ( (configPage1.includeAFR == true) && (configPage3.egoType == 2)) {
iAFR = ((unsigned int)currentStatus.O2 << 7) / currentStatus.afrTarget; //Include AFR (vs target) if enabled
}
iCorrections = (corrections << 7) / 100;
unsigned long intermediate = ((long)REQ_FUEL * (long)iVE) >> 7; //Need to use an intermediate value to avoid overflowing the long
if ( configPage1.multiplyMAP ) {
intermediate = (intermediate * iMAP) >> 7;
if ( configPage1.multiplyMAP == true ) {
intermediate = (intermediate * (unsigned long)iMAP) >> 7;
}
if ( configPage1.includeAFR && (configPage3.egoType == 2)) {
intermediate = (intermediate * iAFR) >> 7; //EGO type must be set to wideband for this to be used
if ( (configPage1.includeAFR == true) && (configPage3.egoType == 2) ) {
intermediate = (intermediate * (unsigned long)iAFR) >> 7; //EGO type must be set to wideband for this to be used
}
intermediate = (intermediate * iCorrections) >> 7;
if (intermediate == 0) {
return 0; //If the pulsewidth is 0, we return here before the opening time gets added
}
intermediate += injOpen; //Add the injector opening time
if ( intermediate > 65535) {
intermediate = 65535; //Make sure this won't overflow when we convert to uInt. This means the maximum pulsewidth possible is 65.535mS
intermediate = (intermediate * (unsigned long)iCorrections) >> 7;
if (intermediate != 0)
{
//If intermeditate is not 0, we need to add the opening time (0 typically indicates that one of the full fuel cuts is active)
intermediate += injOpen; //Add the injector opening time
if ( intermediate > 65535)
{
intermediate = 65535; //Make sure this won't overflow when we convert to uInt. This means the maximum pulsewidth possible is 65.535mS
}
}
return (unsigned int)(intermediate);
@ -640,9 +580,5 @@ unsigned int PW_SD(int REQ_FUEL, byte VE, byte MAP, int corrections, int injOpen
unsigned int PW_AN(int REQ_FUEL, byte VE, byte TPS, int corrections, int injOpen)
{
//Sanity check
if (TPS > 100) {
TPS = 100;
}
return PW(REQ_FUEL, VE, currentStatus.MAP, corrections, injOpen);
}