Merge branch 'master' into pr/5

This commit is contained in:
Vitor Moreno B. Sales 2017-08-28 01:53:24 -03:00 committed by GitHub
commit d8898db9fe
15 changed files with 2567 additions and 2541 deletions

4
.gitignore vendored
View File

@ -10,7 +10,11 @@ table.py
reference/hardware/v0.2/~$schematic v0.2_bom.xlsx
reference/hardware/v0.4/gerbers/Archive.zip
speeduino/.vscode
speeduino/.build
.pioenvs
.piolibdeps
.clang_complete
.gcc-flags.json
.project

0
misra/check_misra.sh Executable file → Normal file
View File

View File

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

View File

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

View File

@ -27,4 +27,4 @@ uint8_t Glow, Ghigh;
void canCommand();//This is the heart of the Command Line Interpeter. All that needed to be done was to make it human readable.
void sendCancommand(uint8_t cmdtype , uint16_t canadddress, uint8_t candata1, uint8_t candata2, uint16_t paramgroup);
#endif // CANCOMMS_H
#endif // CANCOMMS_H

View File

@ -2196,6 +2196,7 @@ void triggerSetEndTeeth_Daihatsu()
}
/* -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
Code for decoder.ino
Name: Harley
@ -2335,3 +2336,4 @@ void triggerSetEndTeeth_Harley()
{
}

View File

@ -36,6 +36,10 @@
#define BIT_SET(a,b) ((a) |= (1<<(b)))
#define BIT_CLEAR(a,b) ((a) &= ~(1<<(b)))
#define BIT_CHECK(var,pos) !!((var) & (1<<(pos)))
#define Lo(param) ((char *)&param)[0]
#define Hi(param) ((char *)&param)[1]
#define Higher(param) ((char *)&param)[2]
#define Highest(param) ((char *)&param)[3]
#define MS_IN_MINUTE 60000
#define US_IN_MINUTE 60000000
@ -124,7 +128,11 @@
#define OFFSET_FUELTRIM 127 //The fuel trim tables are offset by 128 to allow for -128 to +128 values
#define OFFSET_IGNITION 40 //Ignition values from the main spark table are offset 40 degrees downards to allow for negative spark timing
#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
#if defined(CORE_STM32)
#define SERIAL_BUFFER_THRESHOLD 64 // 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 128 bytes long, so the threshold is set at half this as a reasonable figure
#else
#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
#endif
#define FUEL_PUMP_ON() *pump_pin_port |= (pump_pin_mask)
#define FUEL_PUMP_OFF() *pump_pin_port &= ~(pump_pin_mask)
@ -207,6 +215,9 @@ 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 {

View File

@ -404,4 +404,4 @@ static inline unsigned int popQueue(volatile Schedule *queue[])
}
#endif // SCHEDULER_H
#endif // SCHEDULER_H

View File

@ -803,4 +803,4 @@ void ftm0_isr(void)
else if(interrupt8) { FTM0_C7SC &= ~FTM_CSC_CHF; ignitionSchedule4Interrupt(); }
}
#endif
#endif

View File

@ -105,3 +105,4 @@ ISR(ADC_vect)
#endif
#endif // SENSORS_H

View File

@ -268,3 +268,4 @@ void flexPulse()
{
++flexCounter;
}

File diff suppressed because it is too large Load Diff

View File

@ -1,209 +1,212 @@
/*
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
*/
/*
Timers are used for having actions performed repeatedly at a fixed interval (Eg every 100ms)
They should not be confused with Schedulers, which are for performing an action once at a given point of time in the future
Timers are typically low resolution (Compared to Schedulers), with maximum frequency currently being approximately every 10ms
*/
#include "timers.h"
#include "globals.h"
#include "sensors.h"
#if defined(CORE_AVR)
#include <avr/wdt.h>
#endif
void initialiseTimers()
{
#if defined(CORE_AVR) //AVR chips use the ISR for this
//Configure Timer2 for our low-freq interrupt code.
TCCR2B = 0x00; //Disbale Timer2 while we set it up
TCNT2 = 131; //Preload timer2 with 131 cycles, leaving 125 till overflow. As the timer runs at 125Khz, this causes overflow to occur at 1Khz = 1ms
TIFR2 = 0x00; //Timer2 INT Flag Reg: Clear Timer Overflow Flag
TIMSK2 = 0x01; //Timer2 Set Overflow Interrupt enabled.
TCCR2A = 0x00; //Timer2 Control Reg A: Wave Gen Mode normal
/* Now configure the prescaler to CPU clock divided by 128 = 125Khz */
TCCR2B |= (1<<CS22) | (1<<CS20); // Set bits
TCCR2B &= ~(1<<CS21); // Clear bit
//Enable the watchdog timer for 2 second resets (Good reference: https://tushev.org/articles/arduino/5/arduino-and-watchdog-timer)
//Boooooooooo WDT is currently broken on Mega 2560 bootloaders :(
//wdt_enable(WDTO_2S);
#elif defined (CORE_TEENSY)
//Uses the PIT timer on Teensy.
lowResTimer.begin(oneMSInterval, 1000);
#elif defined(CORE_STM32)
Timer4.setPeriod(1000); // Set up period
// Set up an interrupt
Timer4.setMode(1, TIMER_OUTPUT_COMPARE);
Timer4.attachInterrupt(1, oneMSInterval);
Timer4.resume(); //Start Timer
#endif
dwellLimit_uS = (1000 * configPage2.dwellLimit);
lastRPM_100ms = 0;
}
//Timer2 Overflow Interrupt Vector, called when the timer overflows.
//Executes every ~1ms.
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) //AVR chips use the ISR for this
ISR(TIMER2_OVF_vect, ISR_NOBLOCK)
#elif defined (CORE_TEENSY) || defined(CORE_STM32)
void oneMSInterval() //Most ARM chips can simply call a function
#endif
{
//Increment Loop Counters
loop33ms++;
loop66ms++;
loop100ms++;
loop250ms++;
loopSec++;
unsigned long targetOverdwellTime;
//Overdwell check
targetOverdwellTime = micros() - dwellLimit_uS; //Set a target time in the past that all coil charging must have begun after. If the coil charge began before this time, it's been running too long
bool isCrankLocked = configPage2.ignCranklock && (currentStatus.RPM < currentStatus.crankRPM); //Dwell limiter is disabled during cranking on setups using the locked cranking timing. WE HAVE to do the RPM check here as relying on the engine cranking bit can be potentially too slow in updating
//Check first whether each spark output is currently on. Only check it's dwell time if it is
if(ignitionSchedule1.Status == RUNNING) { if( (ignitionSchedule1.startTime < targetOverdwellTime) && (configPage2.useDwellLim) && (isCrankLocked != true) ) { endCoil1Charge(); } }
if(ignitionSchedule2.Status == RUNNING) { if( (ignitionSchedule2.startTime < targetOverdwellTime) && (configPage2.useDwellLim) && (isCrankLocked != true) ) { endCoil2Charge(); } }
if(ignitionSchedule3.Status == RUNNING) { if( (ignitionSchedule3.startTime < targetOverdwellTime) && (configPage2.useDwellLim) && (isCrankLocked != true) ) { endCoil3Charge(); } }
if(ignitionSchedule4.Status == RUNNING) { if( (ignitionSchedule4.startTime < targetOverdwellTime) && (configPage2.useDwellLim) && (isCrankLocked != true) ) { endCoil4Charge(); } }
if(ignitionSchedule5.Status == RUNNING) { if( (ignitionSchedule5.startTime < targetOverdwellTime) && (configPage2.useDwellLim) && (isCrankLocked != true) ) { 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);
#if defined(CORE_STM32) //debug purpose, only visal for running code
digitalWrite(LED_BUILTIN, !digitalRead(LED_BUILTIN));
#endif
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
}
//Loop executed every 250ms loop (1ms x 250 = 250ms)
//Anything inside this if statement will run every 250ms.
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();
//DIY watchdog
if( (initialisationComplete == true) && (last250msLoopCount == mainLoopCount) ) { setup(); } //This is a sign of a crash.
else { last250msLoopCount = mainLoopCount; }
#endif
}
//Loop executed every 1 second (1ms x 1000 = 1000ms)
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
currentStatus.crankRPM = ((unsigned int)configPage2.crankRPM * 100);
//**************************************************************************************************************************************************
//This updates the runSecs variable
//If the engine is running or cranking, we need ot update the run time counter.
if (BIT_CHECK(currentStatus.engine, BIT_ENGINE_RUN))
{ //NOTE - There is a potential for a ~1sec gap between engine crank starting and ths runSec number being incremented. This may delay ASE!
if (currentStatus.runSecs <= 254) //Ensure we cap out at 255 and don't overflow. (which would reset ASE)
{ currentStatus.runSecs++; } //Increment our run counter by 1 second.
}
//**************************************************************************************************************************************************
//This records the number of main loops the system has completed in the last second
currentStatus.loopsPerSecond = mainLoopCount;
mainLoopCount = 0;
//**************************************************************************************************************************************************
//increament secl (secl is simply a counter that increments every second and is used to track whether the system has unexpectedly reset
currentStatus.secl++;
//**************************************************************************************************************************************************
//Check the fan output status
if (configPage4.fanEnable == 1)
{
fanControl(); // Fucntion to turn the cooling fan on/off
}
//Check whether fuel pump priming is complete
if(!fpPrimed)
{
if(currentStatus.secl >= configPage1.fpPrime)
{
fpPrimed = true; //Mark the priming as being completed
if(currentStatus.RPM == 0) { digitalWrite(pinFuelPump, LOW); fuelPumpOn = false; } //If we reach here then the priming is complete, however only turn off the fuel pump if the engine isn't running
}
}
//**************************************************************************************************************************************************
//Set the flex reading (if enabled). The flexCounter is updated with every pulse from the sensor. If cleared once per second, we get a frequency reading
if(configPage1.flexEnabled == true)
{
if(flexCounter < 50)
{
currentStatus.ethanolPct = 0; //Standard GM Continental sensor reads from 50Hz (0 ethanol) to 150Hz (Pure ethanol). Subtracting 50 from the frequency therefore gives the ethanol percentage.
flexCounter = 0;
}
else if (flexCounter > 151) //1 pulse buffer
{
if(flexCounter < 169)
{
currentStatus.ethanolPct = 100;
flexCounter = 0;
}
else
{
//This indicates an error condition. Spec of the sensor is that errors are above 170Hz)
currentStatus.ethanolPct = 0;
flexCounter = 0;
}
}
else
{
currentStatus.ethanolPct = flexCounter - 50; //Standard GM Continental sensor reads from 50Hz (0 ethanol) to 150Hz (Pure ethanol). Subtracting 50 from the frequency therefore gives the ethanol percentage.
flexCounter = 0;
}
//Off by 1 error check
if (currentStatus.ethanolPct == 1) { currentStatus.ethanolPct = 0; }
}
}
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) //AVR chips use the ISR for this
//Reset Timer2 to trigger in another ~1ms
TCNT2 = 131; //Preload timer2 with 100 cycles, leaving 156 till overflow.
TIFR2 = 0x00; //Timer2 INT Flag Reg: Clear Timer Overflow Flag
#endif
/*
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
*/
/*
Timers are used for having actions performed repeatedly at a fixed interval (Eg every 100ms)
They should not be confused with Schedulers, which are for performing an action once at a given point of time in the future
Timers are typically low resolution (Compared to Schedulers), with maximum frequency currently being approximately every 10ms
*/
#include "timers.h"
#include "globals.h"
#include "sensors.h"
#if defined(CORE_AVR)
#include <avr/wdt.h>
#endif
void initialiseTimers()
{
#if defined(CORE_AVR) //AVR chips use the ISR for this
//Configure Timer2 for our low-freq interrupt code.
TCCR2B = 0x00; //Disbale Timer2 while we set it up
TCNT2 = 131; //Preload timer2 with 131 cycles, leaving 125 till overflow. As the timer runs at 125Khz, this causes overflow to occur at 1Khz = 1ms
TIFR2 = 0x00; //Timer2 INT Flag Reg: Clear Timer Overflow Flag
TIMSK2 = 0x01; //Timer2 Set Overflow Interrupt enabled.
TCCR2A = 0x00; //Timer2 Control Reg A: Wave Gen Mode normal
/* Now configure the prescaler to CPU clock divided by 128 = 125Khz */
TCCR2B |= (1<<CS22) | (1<<CS20); // Set bits
TCCR2B &= ~(1<<CS21); // Clear bit
//Enable the watchdog timer for 2 second resets (Good reference: https://tushev.org/articles/arduino/5/arduino-and-watchdog-timer)
//Boooooooooo WDT is currently broken on Mega 2560 bootloaders :(
//wdt_enable(WDTO_2S);
#elif defined (CORE_TEENSY)
//Uses the PIT timer on Teensy.
lowResTimer.begin(oneMSInterval, 1000);
#elif defined(CORE_STM32)
Timer4.setPeriod(1000); // Set up period
// Set up an interrupt
Timer4.setMode(1, TIMER_OUTPUT_COMPARE);
Timer4.attachInterrupt(1, oneMSInterval);
Timer4.resume(); //Start Timer
#endif
#if defined(CORE_STM32)
pinMode(LED_BUILTIN, OUTPUT);
#endif
dwellLimit_uS = (1000 * configPage2.dwellLimit);
lastRPM_100ms = 0;
}
//Timer2 Overflow Interrupt Vector, called when the timer overflows.
//Executes every ~1ms.
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) //AVR chips use the ISR for this
ISR(TIMER2_OVF_vect, ISR_NOBLOCK)
#elif defined (CORE_TEENSY) || defined(CORE_STM32)
void oneMSInterval() //Most ARM chips can simply call a function
#endif
{
//Increment Loop Counters
loop33ms++;
loop66ms++;
loop100ms++;
loop250ms++;
loopSec++;
unsigned long targetOverdwellTime;
//Overdwell check
targetOverdwellTime = micros() - dwellLimit_uS; //Set a target time in the past that all coil charging must have begun after. If the coil charge began before this time, it's been running too long
bool isCrankLocked = configPage2.ignCranklock && (currentStatus.RPM < currentStatus.crankRPM); //Dwell limiter is disabled during cranking on setups using the locked cranking timing. WE HAVE to do the RPM check here as relying on the engine cranking bit can be potentially too slow in updating
//Check first whether each spark output is currently on. Only check it's dwell time if it is
if(ignitionSchedule1.Status == RUNNING) { if( (ignitionSchedule1.startTime < targetOverdwellTime) && (configPage2.useDwellLim) && (isCrankLocked != true) ) { endCoil1Charge(); } }
if(ignitionSchedule2.Status == RUNNING) { if( (ignitionSchedule2.startTime < targetOverdwellTime) && (configPage2.useDwellLim) && (isCrankLocked != true) ) { endCoil2Charge(); } }
if(ignitionSchedule3.Status == RUNNING) { if( (ignitionSchedule3.startTime < targetOverdwellTime) && (configPage2.useDwellLim) && (isCrankLocked != true) ) { endCoil3Charge(); } }
if(ignitionSchedule4.Status == RUNNING) { if( (ignitionSchedule4.startTime < targetOverdwellTime) && (configPage2.useDwellLim) && (isCrankLocked != true) ) { endCoil4Charge(); } }
if(ignitionSchedule5.Status == RUNNING) { if( (ignitionSchedule5.startTime < targetOverdwellTime) && (configPage2.useDwellLim) && (isCrankLocked != true) ) { 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);
#if defined(CORE_STM32) //debug purpose, only visal for running code
digitalWrite(LED_BUILTIN, !digitalRead(LED_BUILTIN));
#endif
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
}
//Loop executed every 250ms loop (1ms x 250 = 250ms)
//Anything inside this if statement will run every 250ms.
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();
//DIY watchdog
if( (initialisationComplete == true) && (last250msLoopCount == mainLoopCount) ) { setup(); } //This is a sign of a crash.
else { last250msLoopCount = mainLoopCount; }
#endif
}
//Loop executed every 1 second (1ms x 1000 = 1000ms)
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
currentStatus.crankRPM = ((unsigned int)configPage2.crankRPM * 100);
//**************************************************************************************************************************************************
//This updates the runSecs variable
//If the engine is running or cranking, we need ot update the run time counter.
if (BIT_CHECK(currentStatus.engine, BIT_ENGINE_RUN))
{ //NOTE - There is a potential for a ~1sec gap between engine crank starting and ths runSec number being incremented. This may delay ASE!
if (currentStatus.runSecs <= 254) //Ensure we cap out at 255 and don't overflow. (which would reset ASE)
{ currentStatus.runSecs++; } //Increment our run counter by 1 second.
}
//**************************************************************************************************************************************************
//This records the number of main loops the system has completed in the last second
currentStatus.loopsPerSecond = mainLoopCount;
mainLoopCount = 0;
//**************************************************************************************************************************************************
//increament secl (secl is simply a counter that increments every second and is used to track whether the system has unexpectedly reset
currentStatus.secl++;
//**************************************************************************************************************************************************
//Check the fan output status
if (configPage4.fanEnable == 1)
{
fanControl(); // Fucntion to turn the cooling fan on/off
}
//Check whether fuel pump priming is complete
if(!fpPrimed)
{
if(currentStatus.secl >= configPage1.fpPrime)
{
fpPrimed = true; //Mark the priming as being completed
if(currentStatus.RPM == 0) { digitalWrite(pinFuelPump, LOW); fuelPumpOn = false; } //If we reach here then the priming is complete, however only turn off the fuel pump if the engine isn't running
}
}
//**************************************************************************************************************************************************
//Set the flex reading (if enabled). The flexCounter is updated with every pulse from the sensor. If cleared once per second, we get a frequency reading
if(configPage1.flexEnabled == true)
{
if(flexCounter < 50)
{
currentStatus.ethanolPct = 0; //Standard GM Continental sensor reads from 50Hz (0 ethanol) to 150Hz (Pure ethanol). Subtracting 50 from the frequency therefore gives the ethanol percentage.
flexCounter = 0;
}
else if (flexCounter > 151) //1 pulse buffer
{
if(flexCounter < 169)
{
currentStatus.ethanolPct = 100;
flexCounter = 0;
}
else
{
//This indicates an error condition. Spec of the sensor is that errors are above 170Hz)
currentStatus.ethanolPct = 0;
flexCounter = 0;
}
}
else
{
currentStatus.ethanolPct = flexCounter - 50; //Standard GM Continental sensor reads from 50Hz (0 ethanol) to 150Hz (Pure ethanol). Subtracting 50 from the frequency therefore gives the ethanol percentage.
flexCounter = 0;
}
//Off by 1 error check
if (currentStatus.ethanolPct == 1) { currentStatus.ethanolPct = 0; }
}
}
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) //AVR chips use the ISR for this
//Reset Timer2 to trigger in another ~1ms
TCNT2 = 131; //Preload timer2 with 100 cycles, leaving 156 till overflow.
TIFR2 = 0x00; //Timer2 INT Flag Reg: Clear Timer Overflow Flag
#endif
}

View File

@ -62,3 +62,4 @@ void doUpdates()
}
}

File diff suppressed because it is too large Load Diff